From 7a0366684ae37eb20d085ce5cc088a5d9ed6fb25 Mon Sep 17 00:00:00 2001 From: krunalchande Date: Wed, 26 Nov 2014 03:54:21 -0500 Subject: [PATCH 001/126] Added Vectors and Matrices. Does not work yet. --- gtsam.h | 10 ++++++++-- 1 file changed, 8 insertions(+), 2 deletions(-) diff --git a/gtsam.h b/gtsam.h index d63563028..bf554986c 100644 --- a/gtsam.h +++ b/gtsam.h @@ -1738,6 +1738,8 @@ class Values { void insert(size_t j, const gtsam::Cal3Bundler& t); void insert(size_t j, const gtsam::EssentialMatrix& t); void insert(size_t j, const gtsam::imuBias::ConstantBias& t); + void insert(size_t j, Vector t); + void insert(size_t j, Matrix t); //git/gtsam/gtsam/base/Manifold.h:254:1: error: invalid application of ‘sizeof’ to incomplete type ‘boost::STATIC_ASSERTION_FAILURE’ void update(size_t j, const gtsam::Point2& t); void update(size_t j, const gtsam::Point3& t); @@ -1750,9 +1752,11 @@ class Values { void update(size_t j, const gtsam::Cal3Bundler& t); void update(size_t j, const gtsam::EssentialMatrix& t); void update(size_t j, const gtsam::imuBias::ConstantBias& t); + void update(size_t j, Vector t); + void update(size_t j, Matrix t); template + gtsam::Rot3, gtsam::Pose3, gtsam::Cal3_S2, gtsam::Cal3DS2, gtsam::imuBias::ConstantBias ,Vector, Matrix}> // Parse Error T at(size_t j); }; @@ -2150,7 +2154,9 @@ class NonlinearISAM { #include #include -template +template // Parse Error virtual class PriorFactor : gtsam::NoiseModelFactor { PriorFactor(size_t key, const T& prior, const gtsam::noiseModel::Base* noiseModel); T prior() const; From 0e9f5c7841db667b015433c2cc7046a4de69d312 Mon Sep 17 00:00:00 2001 From: krunalchande Date: Wed, 26 Nov 2014 03:58:49 -0500 Subject: [PATCH 002/126] Added Vector and Matrix for BetweenFactor --- gtsam.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/gtsam.h b/gtsam.h index bf554986c..b40913229 100644 --- a/gtsam.h +++ b/gtsam.h @@ -2167,7 +2167,7 @@ virtual class PriorFactor : gtsam::NoiseModelFactor { #include -template +template // Parse Error virtual class BetweenFactor : gtsam::NoiseModelFactor { BetweenFactor(size_t key1, size_t key2, const T& relativePose, const gtsam::noiseModel::Base* noiseModel); T measured() const; From 8065a09dc1a24bc6e600bf782abb5934fff47c47 Mon Sep 17 00:00:00 2001 From: dellaert Date: Fri, 28 Nov 2014 11:16:04 +0100 Subject: [PATCH 003/126] Changed implementation to used fixed-size matrices to max extent possible. --- gtsam/navigation/CombinedImuFactor.cpp | 25 +++++ gtsam/navigation/CombinedImuFactor.h | 142 +++++++++++++------------ 2 files changed, 101 insertions(+), 66 deletions(-) create mode 100644 gtsam/navigation/CombinedImuFactor.cpp diff --git a/gtsam/navigation/CombinedImuFactor.cpp b/gtsam/navigation/CombinedImuFactor.cpp new file mode 100644 index 000000000..9448517f2 --- /dev/null +++ b/gtsam/navigation/CombinedImuFactor.cpp @@ -0,0 +1,25 @@ +/* ---------------------------------------------------------------------------- + + * GTSAM Copyright 2010, Georgia Tech Research Corporation, + * Atlanta, Georgia 30332-0415 + * All Rights Reserved + * Authors: Frank Dellaert, et al. (see THANKS for the full author list) + + * See LICENSE for the license information + + * -------------------------------------------------------------------------- */ + +/** + * @file CombinedImuFactor.cpp + * @author Frank Dellaert + * @date Nov 28, 2014 + **/ + +#include + +namespace gtsam { + +const Matrix3 CombinedImuFactor::Z_3x3 = Matrix3::Zero(); +const Matrix3 CombinedImuFactor::I_3x3 = Matrix3::Identity(); + +} /// namespace gtsam diff --git a/gtsam/navigation/CombinedImuFactor.h b/gtsam/navigation/CombinedImuFactor.h index 069723eca..e48a0f053 100644 --- a/gtsam/navigation/CombinedImuFactor.h +++ b/gtsam/navigation/CombinedImuFactor.h @@ -11,7 +11,12 @@ /** * @file CombinedImuFactor.h - * @author Luca Carlone, Stephen Williams, Richard Roberts, Vadim Indelman, David Jensen + * @author Luca Carlone + * @author Stephen Williams + * @author Richard Roberts + * @author Vadim Indelman + * @author David Jensen + * @author Frank Dellaert **/ #pragma once @@ -62,6 +67,9 @@ namespace gtsam { class CombinedImuFactor: public NoiseModelFactor6 { + static const Matrix3 Z_3x3; + static const Matrix3 I_3x3; + public: /** Struct to store results of preintegrating IMU measurements. Can be build @@ -73,7 +81,7 @@ namespace gtsam { friend class CombinedImuFactor; protected: imuBias::ConstantBias biasHat_; ///< Acceleration and angular rate bias values used during preintegration - Matrix measurementCovariance_; ///< (Raw measurements uncertainty) Covariance of the vector + Eigen::Matrix measurementCovariance_; ///< (Raw measurements uncertainty) Covariance of the vector ///< [integrationError measuredAcc measuredOmega biasAccRandomWalk biasOmegaRandomWalk biasAccInit biasOmegaInit] in R^(21 x 21) Vector3 deltaPij_; ///< Preintegrated relative position (does not take into account velocity at time i, see deltap+, in [2]) (in frame i) @@ -86,7 +94,7 @@ namespace gtsam { Matrix3 delVdelBiasAcc_; ///< Jacobian of preintegrated velocity w.r.t. acceleration bias Matrix3 delVdelBiasOmega_; ///< Jacobian of preintegrated velocity w.r.t. angular rate bias Matrix3 delRdelBiasOmega_; ///< Jacobian of preintegrated rotation w.r.t. angular rate bias - Matrix PreintMeasCov_; ///< Covariance matrix of the preintegrated measurements (first-order propagation from *measurementCovariance*) + Eigen::Matrix PreintMeasCov_; ///< Covariance matrix of the preintegrated measurements (first-order propagation from *measurementCovariance*) bool use2ndOrderIntegration_; ///< Controls the order of integration // public: ///< In the combined factor is also includes the biases and keeps the correlation between the preintegrated measurements and the biases @@ -103,30 +111,34 @@ namespace gtsam { const Matrix& biasAccOmegaInit, ///< Covariance of biasAcc & biasOmega when preintegrating measurements const bool use2ndOrderIntegration = false ///< Controls the order of integration ///< (this allows to consider the uncertainty of the BIAS choice when integrating the measurements) - ) : biasHat_(bias), measurementCovariance_(21,21), deltaPij_(Vector3::Zero()), deltaVij_(Vector3::Zero()), deltaTij_(0.0), - delPdelBiasAcc_(Matrix3::Zero()), delPdelBiasOmega_(Matrix3::Zero()), - delVdelBiasAcc_(Matrix3::Zero()), delVdelBiasOmega_(Matrix3::Zero()), - delRdelBiasOmega_(Matrix3::Zero()), PreintMeasCov_(Matrix::Zero(15,15)), + ) : biasHat_(bias), deltaPij_(Vector3::Zero()), deltaVij_(Vector3::Zero()), deltaTij_(0.0), + delPdelBiasAcc_(Z_3x3), delPdelBiasOmega_(Z_3x3), + delVdelBiasAcc_(Z_3x3), delVdelBiasOmega_(Z_3x3), + delRdelBiasOmega_(Z_3x3), use2ndOrderIntegration_(use2ndOrderIntegration) { // COVARIANCE OF: [Integration AccMeasurement OmegaMeasurement BiasAccRandomWalk BiasOmegaRandomWalk (BiasAccInit BiasOmegaInit)] SIZE (21x21) - measurementCovariance_ << integrationErrorCovariance , Matrix3::Zero(), Matrix3::Zero(), Matrix3::Zero(), Matrix3::Zero(), Matrix3::Zero(), Matrix3::Zero(), - Matrix3::Zero(), measuredAccCovariance, Matrix3::Zero(), Matrix3::Zero(), Matrix3::Zero(), Matrix3::Zero(), Matrix3::Zero(), - Matrix3::Zero(), Matrix3::Zero(), measuredOmegaCovariance, Matrix3::Zero(), Matrix3::Zero(), Matrix3::Zero(), Matrix3::Zero(), - Matrix3::Zero(), Matrix3::Zero(), Matrix3::Zero(), biasAccCovariance, Matrix3::Zero(), Matrix3::Zero(), Matrix3::Zero(), - Matrix3::Zero(), Matrix3::Zero(), Matrix3::Zero(), Matrix3::Zero(), biasOmegaCovariance, Matrix3::Zero(), Matrix3::Zero(), - Matrix3::Zero(), Matrix3::Zero(), Matrix3::Zero(), Matrix3::Zero(), Matrix3::Zero(), biasAccOmegaInit.block(0,0,3,3), biasAccOmegaInit.block(0,3,3,3), - Matrix3::Zero(), Matrix3::Zero(), Matrix3::Zero(), Matrix3::Zero(), Matrix3::Zero(), biasAccOmegaInit.block(3,0,3,3), biasAccOmegaInit.block(3,3,3,3); + measurementCovariance_.setZero(); + measurementCovariance_.block<3,3>(0,0) = integrationErrorCovariance; + measurementCovariance_.block<3,3>(3,3) = measuredAccCovariance; + measurementCovariance_.block<3,3>(6,6) = measuredOmegaCovariance; + measurementCovariance_.block<3,3>(9,9) = biasAccCovariance; + measurementCovariance_.block<3,3>(12,12) = biasOmegaCovariance; + measurementCovariance_.block<6,6>(15,15) = biasAccOmegaInit; + PreintMeasCov_.setZero(); } + // TODO: in what context is this constructor used and why do you init to zero? + // measurementCovariance_ was is not initialized, BTW CombinedPreintegratedMeasurements() : - biasHat_(imuBias::ConstantBias()), measurementCovariance_(21,21), deltaPij_(Vector3::Zero()), deltaVij_(Vector3::Zero()), deltaTij_(0.0), - delPdelBiasAcc_(Matrix3::Zero()), delPdelBiasOmega_(Matrix3::Zero()), - delVdelBiasAcc_(Matrix3::Zero()), delVdelBiasOmega_(Matrix3::Zero()), - delRdelBiasOmega_(Matrix3::Zero()), PreintMeasCov_(Matrix::Zero(15,15)), + biasHat_(imuBias::ConstantBias()), deltaPij_(Vector3::Zero()), deltaVij_(Vector3::Zero()), deltaTij_(0.0), + delPdelBiasAcc_(Z_3x3), delPdelBiasOmega_(Z_3x3), + delVdelBiasAcc_(Z_3x3), delVdelBiasOmega_(Z_3x3), + delRdelBiasOmega_(Z_3x3), use2ndOrderIntegration_(false) ///< Controls the order of integration { + PreintMeasCov_.setZero(); } /** print */ @@ -161,12 +173,12 @@ namespace gtsam { deltaVij_ = Vector3::Zero(); deltaRij_ = Rot3(); deltaTij_ = 0.0; - delPdelBiasAcc_ = Matrix3::Zero(); - delPdelBiasOmega_ = Matrix3::Zero(); - delVdelBiasAcc_ = Matrix3::Zero(); - delVdelBiasOmega_ = Matrix3::Zero(); - delRdelBiasOmega_ = Matrix3::Zero(); - PreintMeasCov_ = Matrix::Zero(15,15); + delPdelBiasAcc_ = Z_3x3; + delPdelBiasOmega_ = Z_3x3; + delVdelBiasAcc_ = Z_3x3; + delVdelBiasOmega_ = Z_3x3; + delRdelBiasOmega_ = Z_3x3; + PreintMeasCov_.setZero(); } /** Add a single IMU measurement to the preintegration. */ @@ -213,8 +225,6 @@ namespace gtsam { // can be seen as a prediction phase in an EKF framework. In this implementation, contrarily to [2] we // consider the uncertainty of the bias selection and we keep correlation between biases and preintegrated measurements /* ----------------------------------------------------------------------------------------------------------------------- */ - Matrix3 Z_3x3 = Matrix3::Zero(); - Matrix3 I_3x3 = Matrix3::Identity(); const Vector3 theta_i = Rot3::Logmap(deltaRij_); // parametrization of so(3) const Matrix3 Jr_theta_i = Rot3::rightJacobianExpMapSO3(theta_i); @@ -255,24 +265,24 @@ namespace gtsam { Matrix G_measCov_Gt = Matrix::Zero(15,15); // BLOCK DIAGONAL TERMS - G_measCov_Gt.block(0,0,3,3) = deltaT * measurementCovariance_.block(0,0,3,3); + G_measCov_Gt.block<3,3>(0,0) = deltaT * measurementCovariance_.block<3,3>(0,0); - G_measCov_Gt.block(3,3,3,3) = (1/deltaT) * (H_vel_biasacc) * - (measurementCovariance_.block(3,3,3,3) + measurementCovariance_.block(15,15,3,3) ) * + G_measCov_Gt.block<3,3>(3,3) = (1/deltaT) * (H_vel_biasacc) * + (measurementCovariance_.block<3,3>(3,3) + measurementCovariance_.block<3,3>(15,15) ) * (H_vel_biasacc.transpose()); - G_measCov_Gt.block(6,6,3,3) = (1/deltaT) * (H_angles_biasomega) * - (measurementCovariance_.block(6,6,3,3) + measurementCovariance_.block(18,18,3,3) ) * + G_measCov_Gt.block<3,3>(6,6) = (1/deltaT) * (H_angles_biasomega) * + (measurementCovariance_.block<3,3>(6,6) + measurementCovariance_.block<3,3>(18,18) ) * (H_angles_biasomega.transpose()); - G_measCov_Gt.block(9,9,3,3) = deltaT * measurementCovariance_.block(9,9,3,3); + G_measCov_Gt.block<3,3>(9,9) = deltaT * measurementCovariance_.block<3,3>(9,9); - G_measCov_Gt.block(12,12,3,3) = deltaT * measurementCovariance_.block(12,12,3,3); + G_measCov_Gt.block<3,3>(12,12) = deltaT * measurementCovariance_.block<3,3>(12,12); // NEW OFF BLOCK DIAGONAL TERMS - Matrix3 block23 = H_vel_biasacc * measurementCovariance_.block(18,15,3,3) * H_angles_biasomega.transpose(); - G_measCov_Gt.block(3,6,3,3) = block23; - G_measCov_Gt.block(6,3,3,3) = block23.transpose(); + Matrix3 block23 = H_vel_biasacc * measurementCovariance_.block<3,3>(18,15) * H_angles_biasomega.transpose(); + G_measCov_Gt.block<3,3>(3,6) = block23; + G_measCov_Gt.block<3,3>(6,3) = block23.transpose(); PreintMeasCov_ = F * PreintMeasCov_ * F.transpose() + G_measCov_Gt; @@ -370,7 +380,7 @@ namespace gtsam { #endif /** Default constructor - only use for serialization */ - CombinedImuFactor() : preintegratedMeasurements_(imuBias::ConstantBias(), Matrix3::Zero(), Matrix3::Zero(), Matrix3::Zero(), Matrix3::Zero(), Matrix3::Zero(), Matrix::Zero(6,6)) {} + CombinedImuFactor() : preintegratedMeasurements_(imuBias::ConstantBias(), Z_3x3, Z_3x3, Z_3x3, Z_3x3, Z_3x3, Matrix::Zero(6,6)) {} /** Constructor */ CombinedImuFactor( @@ -482,7 +492,7 @@ namespace gtsam { const Matrix3 Jrinv_fRhat = Rot3::rightJacobianExpMapSO3inverse(Rot3::Logmap(fRhat)); - /* + /* TODO why is this commented out. Put it on a branch but remove from develop? (*H1) << // dfP/dRi Rot_i.matrix() * skewSymmetric(preintegratedMeasurements_.deltaPij @@ -497,11 +507,11 @@ namespace gtsam { // dfR/dRi Jrinv_fRhat * (- Rot_j.between(Rot_i).matrix() - fRhat.inverse().matrix() * Jtheta), // dfR/dPi - Matrix3::Zero(), + Z_3x3, //dBiasAcc/dPi - Matrix3::Zero(), Matrix3::Zero(), + Z_3x3, Z_3x3, //dBiasOmega/dPi - Matrix3::Zero(), Matrix3::Zero(); + Z_3x3, Z_3x3; */ if(H1) { H1->resize(15,6); @@ -514,7 +524,7 @@ namespace gtsam { } else{ dfPdPi = - Rot_i.matrix(); - dfVdPi = Matrix3::Zero(); + dfVdPi = Z_3x3; } (*H1) << @@ -531,28 +541,28 @@ namespace gtsam { // dfR/dRi Jrinv_fRhat * (- Rot_j.between(Rot_i).matrix() - fRhat.inverse().matrix() * Jtheta), // dfR/dPi - Matrix3::Zero(), + Z_3x3, //dBiasAcc/dPi - Matrix3::Zero(), Matrix3::Zero(), + Z_3x3, Z_3x3, //dBiasOmega/dPi - Matrix3::Zero(), Matrix3::Zero(); + Z_3x3, Z_3x3; } if(H2) { H2->resize(15,3); (*H2) << // dfP/dVi - - Matrix3::Identity() * deltaTij + - I_3x3 * deltaTij + skewSymmetric(omegaCoriolis_) * deltaTij * deltaTij, // Coriolis term - we got rid of the 2 wrt ins paper // dfV/dVi - - Matrix3::Identity() + - I_3x3 + 2 * skewSymmetric(omegaCoriolis_) * deltaTij, // Coriolis term // dfR/dVi - Matrix3::Zero(), + Z_3x3, //dBiasAcc/dVi - Matrix3::Zero(), + Z_3x3, //dBiasOmega/dVi - Matrix3::Zero(); + Z_3x3; } if(H3) { @@ -560,30 +570,30 @@ namespace gtsam { H3->resize(15,6); (*H3) << // dfP/dPosej - Matrix3::Zero(), Rot_j.matrix(), + Z_3x3, Rot_j.matrix(), // dfV/dPosej Matrix::Zero(3,6), // dfR/dPosej - Jrinv_fRhat * ( Matrix3::Identity() ), Matrix3::Zero(), + Jrinv_fRhat * ( I_3x3 ), Z_3x3, //dBiasAcc/dPosej - Matrix3::Zero(), Matrix3::Zero(), + Z_3x3, Z_3x3, //dBiasOmega/dPosej - Matrix3::Zero(), Matrix3::Zero(); + Z_3x3, Z_3x3; } if(H4) { H4->resize(15,3); (*H4) << // dfP/dVj - Matrix3::Zero(), + Z_3x3, // dfV/dVj - Matrix3::Identity(), + I_3x3, // dfR/dVj - Matrix3::Zero(), + Z_3x3, //dBiasAcc/dVj - Matrix3::Zero(), + Z_3x3, //dBiasOmega/dVj - Matrix3::Zero(); + Z_3x3; } if(H5) { @@ -603,9 +613,9 @@ namespace gtsam { Matrix::Zero(3,3), Jrinv_fRhat * ( - fRhat.inverse().matrix() * JbiasOmega), //dBiasAcc/dBias_i - -Matrix3::Identity(), Matrix3::Zero(), + -I_3x3, Z_3x3, //dBiasOmega/dBias_i - Matrix3::Zero(), -Matrix3::Identity(); + Z_3x3, -I_3x3; } if(H6) { @@ -613,15 +623,15 @@ namespace gtsam { H6->resize(15,6); (*H6) << // dfP/dBias_j - Matrix3::Zero(), Matrix3::Zero(), + Z_3x3, Z_3x3, // dfV/dBias_j - Matrix3::Zero(), Matrix3::Zero(), + Z_3x3, Z_3x3, // dfR/dBias_j - Matrix3::Zero(), Matrix3::Zero(), + Z_3x3, Z_3x3, //dBiasAcc/dBias_j - Matrix3::Identity(), Matrix3::Zero(), + I_3x3, Z_3x3, //dBiasOmega/dBias_j - Matrix3::Zero(), Matrix3::Identity(); + Z_3x3, I_3x3; } // Evaluate residual error, according to [3] From 428cde23793618003c709e645ae6f0d23e558d1a Mon Sep 17 00:00:00 2001 From: dellaert Date: Fri, 28 Nov 2014 12:31:40 +0100 Subject: [PATCH 004/126] Added two coomnly used constants --- gtsam/base/Matrix.h | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/gtsam/base/Matrix.h b/gtsam/base/Matrix.h index 132bf79ad..9c273f78c 100644 --- a/gtsam/base/Matrix.h +++ b/gtsam/base/Matrix.h @@ -63,6 +63,10 @@ typedef Eigen::Matrix Matrix39; typedef Eigen::Block SubMatrix; typedef Eigen::Block ConstSubMatrix; +// Two very commonly used matrices: +const Matrix3 Z_3x3 = Matrix3::Zero(); +const Matrix3 I_3x3 = Matrix3::Identity(); + // Matlab-like syntax /** From a12be48af09bc43ee82be9b7a9aa330738805ae8 Mon Sep 17 00:00:00 2001 From: dellaert Date: Fri, 28 Nov 2014 12:32:06 +0100 Subject: [PATCH 005/126] Now use Matrix.h constants --- gtsam/navigation/CombinedImuFactor.cpp | 25 -------- gtsam/navigation/CombinedImuFactor.h | 3 - gtsam/navigation/ImuFactor.h | 59 ++++++++++--------- .../tests/testCombinedImuFactor.cpp | 13 ++-- 4 files changed, 39 insertions(+), 61 deletions(-) delete mode 100644 gtsam/navigation/CombinedImuFactor.cpp diff --git a/gtsam/navigation/CombinedImuFactor.cpp b/gtsam/navigation/CombinedImuFactor.cpp deleted file mode 100644 index 9448517f2..000000000 --- a/gtsam/navigation/CombinedImuFactor.cpp +++ /dev/null @@ -1,25 +0,0 @@ -/* ---------------------------------------------------------------------------- - - * GTSAM Copyright 2010, Georgia Tech Research Corporation, - * Atlanta, Georgia 30332-0415 - * All Rights Reserved - * Authors: Frank Dellaert, et al. (see THANKS for the full author list) - - * See LICENSE for the license information - - * -------------------------------------------------------------------------- */ - -/** - * @file CombinedImuFactor.cpp - * @author Frank Dellaert - * @date Nov 28, 2014 - **/ - -#include - -namespace gtsam { - -const Matrix3 CombinedImuFactor::Z_3x3 = Matrix3::Zero(); -const Matrix3 CombinedImuFactor::I_3x3 = Matrix3::Identity(); - -} /// namespace gtsam diff --git a/gtsam/navigation/CombinedImuFactor.h b/gtsam/navigation/CombinedImuFactor.h index e48a0f053..a60b9ba07 100644 --- a/gtsam/navigation/CombinedImuFactor.h +++ b/gtsam/navigation/CombinedImuFactor.h @@ -67,9 +67,6 @@ namespace gtsam { class CombinedImuFactor: public NoiseModelFactor6 { - static const Matrix3 Z_3x3; - static const Matrix3 I_3x3; - public: /** Struct to store results of preintegrating IMU measurements. Can be build diff --git a/gtsam/navigation/ImuFactor.h b/gtsam/navigation/ImuFactor.h index d1b8a9d80..b6205edf8 100644 --- a/gtsam/navigation/ImuFactor.h +++ b/gtsam/navigation/ImuFactor.h @@ -11,7 +11,12 @@ /** * @file ImuFactor.h - * @author Luca Carlone, Stephen Williams, Richard Roberts, Vadim Indelman, David Jensen + * @author Luca Carlone + * @author Stephen Williams + * @author Richard Roberts + * @author Vadim Indelman + * @author David Jensen + * @author Frank Dellaert **/ #pragma once @@ -90,21 +95,21 @@ struct PoseVelocity { const Matrix3& integrationErrorCovariance, ///< Covariance matrix of integration errors const bool use2ndOrderIntegration = false ///< Controls the order of integration ) : biasHat_(bias), measurementCovariance_(9,9), deltaPij_(Vector3::Zero()), deltaVij_(Vector3::Zero()), deltaTij_(0.0), - delPdelBiasAcc_(Matrix3::Zero()), delPdelBiasOmega_(Matrix3::Zero()), - delVdelBiasAcc_(Matrix3::Zero()), delVdelBiasOmega_(Matrix3::Zero()), - delRdelBiasOmega_(Matrix3::Zero()), PreintMeasCov_(9,9), use2ndOrderIntegration_(use2ndOrderIntegration) + delPdelBiasAcc_(Z_3x3), delPdelBiasOmega_(Z_3x3), + delVdelBiasAcc_(Z_3x3), delVdelBiasOmega_(Z_3x3), + delRdelBiasOmega_(Z_3x3), PreintMeasCov_(9,9), use2ndOrderIntegration_(use2ndOrderIntegration) { - measurementCovariance_ << integrationErrorCovariance , Matrix3::Zero(), Matrix3::Zero(), - Matrix3::Zero(), measuredAccCovariance, Matrix3::Zero(), - Matrix3::Zero(), Matrix3::Zero(), measuredOmegaCovariance; + measurementCovariance_ << integrationErrorCovariance , Z_3x3, Z_3x3, + Z_3x3, measuredAccCovariance, Z_3x3, + Z_3x3, Z_3x3, measuredOmegaCovariance; PreintMeasCov_ = Matrix::Zero(9,9); } PreintegratedMeasurements() : biasHat_(imuBias::ConstantBias()), measurementCovariance_(9,9), deltaPij_(Vector3::Zero()), deltaVij_(Vector3::Zero()), deltaTij_(0.0), - delPdelBiasAcc_(Matrix3::Zero()), delPdelBiasOmega_(Matrix3::Zero()), - delVdelBiasAcc_(Matrix3::Zero()), delVdelBiasOmega_(Matrix3::Zero()), - delRdelBiasOmega_(Matrix3::Zero()), PreintMeasCov_(9,9), use2ndOrderIntegration_(false) + delPdelBiasAcc_(Z_3x3), delPdelBiasOmega_(Z_3x3), + delVdelBiasAcc_(Z_3x3), delVdelBiasOmega_(Z_3x3), + delRdelBiasOmega_(Z_3x3), PreintMeasCov_(9,9), use2ndOrderIntegration_(false) { measurementCovariance_ = Matrix::Zero(9,9); PreintMeasCov_ = Matrix::Zero(9,9); @@ -155,11 +160,11 @@ struct PoseVelocity { deltaVij_ = Vector3::Zero(); deltaRij_ = Rot3(); deltaTij_ = 0.0; - delPdelBiasAcc_ = Matrix3::Zero(); - delPdelBiasOmega_ = Matrix3::Zero(); - delVdelBiasAcc_ = Matrix3::Zero(); - delVdelBiasOmega_ = Matrix3::Zero(); - delRdelBiasOmega_ = Matrix3::Zero(); + delPdelBiasAcc_ = Z_3x3; + delPdelBiasOmega_ = Z_3x3; + delVdelBiasAcc_ = Z_3x3; + delVdelBiasOmega_ = Z_3x3; + delRdelBiasOmega_ = Z_3x3; PreintMeasCov_ = Matrix::Zero(9,9); } @@ -206,8 +211,6 @@ struct PoseVelocity { // Update preintegrated measurements covariance /* ----------------------------------------------------------------------------------------------------------------------- */ - Matrix3 Z_3x3 = Matrix3::Zero(); - Matrix3 I_3x3 = Matrix3::Identity(); const Vector3 theta_i = Rot3::Logmap(deltaRij_); // parametrization of so(3) const Matrix3 Jr_theta_i = Rot3::rightJacobianExpMapSO3(theta_i); @@ -336,7 +339,7 @@ struct PoseVelocity { #endif /** Default constructor - only use for serialization */ - ImuFactor() : preintegratedMeasurements_(imuBias::ConstantBias(), Matrix3::Zero(), Matrix3::Zero(), Matrix3::Zero()), use2ndOrderCoriolis_(false){} + ImuFactor() : preintegratedMeasurements_(imuBias::ConstantBias(), Z_3x3, Z_3x3, Z_3x3), use2ndOrderCoriolis_(false){} /** Constructor */ ImuFactor( @@ -456,7 +459,7 @@ struct PoseVelocity { } else{ dfPdPi = - Rot_i.matrix(); - dfVdPi = Matrix3::Zero(); + dfVdPi = Z_3x3; } (*H1) << @@ -473,20 +476,20 @@ struct PoseVelocity { // dfR/dRi Jrinv_fRhat * (- Rot_j.between(Rot_i).matrix() - fRhat.inverse().matrix() * Jtheta), // dfR/dPi - Matrix3::Zero(); + Z_3x3; } if(H2) { H2->resize(9,3); (*H2) << // dfP/dVi - - Matrix3::Identity() * deltaTij + - I_3x3 * deltaTij + skewSymmetric(omegaCoriolis_) * deltaTij * deltaTij, // Coriolis term - we got rid of the 2 wrt ins paper // dfV/dVi - - Matrix3::Identity() + - I_3x3 + 2 * skewSymmetric(omegaCoriolis_) * deltaTij, // Coriolis term // dfR/dVi - Matrix3::Zero(); + Z_3x3; } if(H3) { @@ -494,22 +497,22 @@ struct PoseVelocity { H3->resize(9,6); (*H3) << // dfP/dPosej - Matrix3::Zero(), Rot_j.matrix(), + Z_3x3, Rot_j.matrix(), // dfV/dPosej Matrix::Zero(3,6), // dfR/dPosej - Jrinv_fRhat * ( Matrix3::Identity() ), Matrix3::Zero(); + Jrinv_fRhat * ( I_3x3 ), Z_3x3; } if(H4) { H4->resize(9,3); (*H4) << // dfP/dVj - Matrix3::Zero(), + Z_3x3, // dfV/dVj - Matrix3::Identity(), + I_3x3, // dfR/dVj - Matrix3::Zero(); + Z_3x3; } if(H5) { diff --git a/gtsam/navigation/tests/testCombinedImuFactor.cpp b/gtsam/navigation/tests/testCombinedImuFactor.cpp index fda82eca9..aab38f258 100644 --- a/gtsam/navigation/tests/testCombinedImuFactor.cpp +++ b/gtsam/navigation/tests/testCombinedImuFactor.cpp @@ -10,19 +10,22 @@ * -------------------------------------------------------------------------- */ /** - * @file testImuFactor.cpp - * @brief Unit test for ImuFactor - * @author Luca Carlone, Stephen Williams, Richard Roberts + * @file testCombinedImuFactor.cpp + * @brief Unit test for Lupton-style combined IMU factor + * @author Luca Carlone + * @author Stephen Williams + * @author Richard Roberts */ -#include -#include #include #include #include #include +#include +#include #include #include + #include #include From 667673e9a9c2c819a991565908da5ed4eb19fb90 Mon Sep 17 00:00:00 2001 From: dellaert Date: Fri, 28 Nov 2014 12:41:20 +0100 Subject: [PATCH 006/126] Fixed size matrix --- gtsam/navigation/ImuFactor.h | 18 +++++++++--------- 1 file changed, 9 insertions(+), 9 deletions(-) diff --git a/gtsam/navigation/ImuFactor.h b/gtsam/navigation/ImuFactor.h index b6205edf8..78ad6efcb 100644 --- a/gtsam/navigation/ImuFactor.h +++ b/gtsam/navigation/ImuFactor.h @@ -72,7 +72,7 @@ struct PoseVelocity { friend class ImuFactor; protected: imuBias::ConstantBias biasHat_; ///< Acceleration and angular rate bias values used during preintegration - Matrix measurementCovariance_; ///< (continuous-time uncertainty) Covariance of the vector [integrationError measuredAcc measuredOmega] in R^(9X9) + Eigen::Matrix measurementCovariance_; ///< (continuous-time uncertainty) Covariance of the vector [integrationError measuredAcc measuredOmega] in R^(9X9) Vector3 deltaPij_; ///< Preintegrated relative position (does not take into account velocity at time i, see deltap+, in [2]) (in frame i) Vector3 deltaVij_; ///< Preintegrated relative velocity (in global frame) @@ -84,7 +84,7 @@ struct PoseVelocity { Matrix3 delVdelBiasAcc_; ///< Jacobian of preintegrated velocity w.r.t. acceleration bias Matrix3 delVdelBiasOmega_; ///< Jacobian of preintegrated velocity w.r.t. angular rate bias Matrix3 delRdelBiasOmega_; ///< Jacobian of preintegrated rotation w.r.t. angular rate bias - Matrix PreintMeasCov_; ///< Covariance matrix of the preintegrated measurements (first-order propagation from *measurementCovariance*) + Eigen::Matrix PreintMeasCov_; ///< Covariance matrix of the preintegrated measurements (first-order propagation from *measurementCovariance*) bool use2ndOrderIntegration_; ///< Controls the order of integration public: /** Default constructor, initialize with no IMU measurements */ @@ -94,25 +94,25 @@ struct PoseVelocity { const Matrix3& measuredOmegaCovariance, ///< Covariance matrix of measured Angular Rate const Matrix3& integrationErrorCovariance, ///< Covariance matrix of integration errors const bool use2ndOrderIntegration = false ///< Controls the order of integration - ) : biasHat_(bias), measurementCovariance_(9,9), deltaPij_(Vector3::Zero()), deltaVij_(Vector3::Zero()), deltaTij_(0.0), + ) : biasHat_(bias), deltaPij_(Vector3::Zero()), deltaVij_(Vector3::Zero()), deltaTij_(0.0), delPdelBiasAcc_(Z_3x3), delPdelBiasOmega_(Z_3x3), delVdelBiasAcc_(Z_3x3), delVdelBiasOmega_(Z_3x3), - delRdelBiasOmega_(Z_3x3), PreintMeasCov_(9,9), use2ndOrderIntegration_(use2ndOrderIntegration) + delRdelBiasOmega_(Z_3x3), use2ndOrderIntegration_(use2ndOrderIntegration) { measurementCovariance_ << integrationErrorCovariance , Z_3x3, Z_3x3, Z_3x3, measuredAccCovariance, Z_3x3, Z_3x3, Z_3x3, measuredOmegaCovariance; - PreintMeasCov_ = Matrix::Zero(9,9); + PreintMeasCov_.setZero(9,9); } PreintegratedMeasurements() : - biasHat_(imuBias::ConstantBias()), measurementCovariance_(9,9), deltaPij_(Vector3::Zero()), deltaVij_(Vector3::Zero()), deltaTij_(0.0), + biasHat_(imuBias::ConstantBias()), deltaPij_(Vector3::Zero()), deltaVij_(Vector3::Zero()), deltaTij_(0.0), delPdelBiasAcc_(Z_3x3), delPdelBiasOmega_(Z_3x3), delVdelBiasAcc_(Z_3x3), delVdelBiasOmega_(Z_3x3), - delRdelBiasOmega_(Z_3x3), PreintMeasCov_(9,9), use2ndOrderIntegration_(false) + delRdelBiasOmega_(Z_3x3), use2ndOrderIntegration_(false) { - measurementCovariance_ = Matrix::Zero(9,9); - PreintMeasCov_ = Matrix::Zero(9,9); + measurementCovariance_.setZero(9,9); + PreintMeasCov_.setZero(9,9); } /** print */ From c90bc5c34a037c7cd896c37eae7415087e23eba3 Mon Sep 17 00:00:00 2001 From: dellaert Date: Fri, 28 Nov 2014 01:58:11 +0100 Subject: [PATCH 007/126] Excluded Paul's test --- gtsam_unstable/nonlinear/tests/CMakeLists.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/gtsam_unstable/nonlinear/tests/CMakeLists.txt b/gtsam_unstable/nonlinear/tests/CMakeLists.txt index 5b1fd07d4..ad14fcd9b 100644 --- a/gtsam_unstable/nonlinear/tests/CMakeLists.txt +++ b/gtsam_unstable/nonlinear/tests/CMakeLists.txt @@ -1 +1 @@ -gtsamAddTestsGlob(nonlinear_unstable "test*.cpp" "" "gtsam_unstable") +gtsamAddTestsGlob(nonlinear_unstable "test*.cpp" "testCustomChartExpression.cpp" "gtsam_unstable") From 18a8de1f466786512e685b37cc2cbf8e8bb503df Mon Sep 17 00:00:00 2001 From: HannesSommer Date: Sat, 29 Nov 2014 10:14:19 +0100 Subject: [PATCH 008/126] - unrolled the reverseAD recursion - MaxVirtualStaticRows is now a macro and some preprocessor derictives activate and deactivate the corresponding defintions. This could be of course removed at some point. --- gtsam_unstable/nonlinear/CallRecord.h | 151 ++++++++++-------- .../nonlinear/tests/testCallRecord.cpp | 2 +- 2 files changed, 83 insertions(+), 70 deletions(-) diff --git a/gtsam_unstable/nonlinear/CallRecord.h b/gtsam_unstable/nonlinear/CallRecord.h index f1ac0b044..5a1fdadc4 100644 --- a/gtsam_unstable/nonlinear/CallRecord.h +++ b/gtsam_unstable/nonlinear/CallRecord.h @@ -36,7 +36,7 @@ class JacobianMap; * MaxVirtualStaticRows defines how many separate virtual reverseAD with specific * static rows (1..MaxVirtualStaticRows) methods will be part of the CallRecord interface. */ -const int MaxVirtualStaticRows = 4; +#define MaxVirtualStaticRows 4 namespace internal { @@ -69,65 +69,6 @@ struct ConvertToVirtualFunctionSupportedMatrixType { } }; -/** - * Recursive definition of an interface having several purely - * virtual _reverseAD(const Eigen::Matrix &, JacobianMap&) - * with Rows in 1..MaxSupportedStaticRows - */ -template -struct ReverseADInterface: ReverseADInterface { - using ReverseADInterface::_reverseAD; - virtual void _reverseAD( - const Eigen::Matrix & dFdT, - JacobianMap& jacobians) const = 0; -}; - -template -struct ReverseADInterface<0, Cols> { - virtual void _reverseAD( - const Eigen::Matrix & dFdT, - JacobianMap& jacobians) const = 0; - virtual void _reverseAD(const Matrix & dFdT, - JacobianMap& jacobians) const = 0; -}; - -/** - * ReverseADImplementor is a utility class used by CallRecordImplementor to - * implementing the recursive ReverseADInterface interface. - */ -template -struct ReverseADImplementor: ReverseADImplementor { -private: - using ReverseADImplementor::_reverseAD; - virtual void _reverseAD( - const Eigen::Matrix & dFdT, - JacobianMap& jacobians) const { - static_cast(this)->reverseAD(dFdT, jacobians); - } - friend struct internal::ReverseADImplementor; -}; - -template -struct ReverseADImplementor : virtual internal::ReverseADInterface< - MaxVirtualStaticRows, Cols> { -private: - using internal::ReverseADInterface::_reverseAD; - const Derived & derived() const { - return static_cast(*this); - } - virtual void _reverseAD( - const Eigen::Matrix & dFdT, - JacobianMap& jacobians) const { - derived().reverseAD(dFdT, jacobians); - } - virtual void _reverseAD(const Matrix & dFdT, JacobianMap& jacobians) const { - derived().reverseAD(dFdT, jacobians); - } - friend struct internal::ReverseADImplementor; -}; - } // namespace internal /** @@ -138,9 +79,7 @@ private: * It is implemented in the function-style ExpressionNode's nested Record class below. */ template -struct CallRecord: virtual private internal::ReverseADInterface< - MaxVirtualStaticRows, Cols> { - +struct CallRecord { inline void print(const std::string& indent) const { _print(indent); } @@ -153,8 +92,11 @@ struct CallRecord: virtual private internal::ReverseADInterface< inline void reverseAD(const Eigen::MatrixBase & dFdT, JacobianMap& jacobians) const { _reverseAD( - internal::ConvertToVirtualFunctionSupportedMatrixType<(Derived::RowsAtCompileTime > MaxVirtualStaticRows)>::convert( - dFdT), jacobians); + internal::ConvertToVirtualFunctionSupportedMatrixType< + (Derived::RowsAtCompileTime > MaxVirtualStaticRows) + >::convert(dFdT), + jacobians + ); } inline void reverseAD(const Matrix & dFdT, JacobianMap& jacobians) const { @@ -167,7 +109,36 @@ struct CallRecord: virtual private internal::ReverseADInterface< private: virtual void _print(const std::string& indent) const = 0; virtual void _startReverseAD(JacobianMap& jacobians) const = 0; - using internal::ReverseADInterface::_reverseAD; + + virtual void _reverseAD(const Matrix & dFdT, JacobianMap& jacobians) const = 0; + virtual void _reverseAD( + const Eigen::Matrix & dFdT, + JacobianMap& jacobians) const = 0; +#if MaxVirtualStaticRows >= 1 + virtual void _reverseAD( + const Eigen::Matrix & dFdT, + JacobianMap& jacobians) const = 0; +#endif +#if MaxVirtualStaticRows >= 2 + virtual void _reverseAD( + const Eigen::Matrix & dFdT, + JacobianMap& jacobians) const = 0; +#endif +#if MaxVirtualStaticRows >= 3 + virtual void _reverseAD( + const Eigen::Matrix & dFdT, + JacobianMap& jacobians) const = 0; +#endif +#if MaxVirtualStaticRows >= 4 + virtual void _reverseAD( + const Eigen::Matrix & dFdT, + JacobianMap& jacobians) const = 0; +#endif +#if MaxVirtualStaticRows >= 5 + virtual void _reverseAD( + const Eigen::Matrix & dFdT, + JacobianMap& jacobians) const = 0; +#endif }; namespace internal { @@ -176,8 +147,7 @@ namespace internal { * delegating to its corresponding (templated) non-virtual methods. */ template -struct CallRecordImplementor: public CallRecord, - private ReverseADImplementor { +struct CallRecordImplementor: public CallRecord { private: const Derived & derived() const { return static_cast(*this); @@ -188,7 +158,50 @@ private: virtual void _startReverseAD(JacobianMap& jacobians) const { derived().startReverseAD(jacobians); } - template friend struct ReverseADImplementor; + + virtual void _reverseAD(const Matrix & dFdT, JacobianMap& jacobians) const { + derived().reverseAD(dFdT, jacobians); + } + virtual void _reverseAD( + const Eigen::Matrix & dFdT, + JacobianMap& jacobians) const { + derived().reverseAD(dFdT, jacobians); + } +#if MaxVirtualStaticRows >= 1 + virtual void _reverseAD( + const Eigen::Matrix & dFdT, + JacobianMap& jacobians) const { + derived().reverseAD(dFdT, jacobians); + } +#endif +#if MaxVirtualStaticRows >= 2 + virtual void _reverseAD( + const Eigen::Matrix & dFdT, + JacobianMap& jacobians) const { + derived().reverseAD(dFdT, jacobians); + } +#endif +#if MaxVirtualStaticRows >= 3 + virtual void _reverseAD( + const Eigen::Matrix & dFdT, + JacobianMap& jacobians) const { + derived().reverseAD(dFdT, jacobians); + } +#endif +#if MaxVirtualStaticRows >= 4 + virtual void _reverseAD( + const Eigen::Matrix & dFdT, + JacobianMap& jacobians) const { + derived().reverseAD(dFdT, jacobians); + } +#endif +#if MaxVirtualStaticRows >= 5 + virtual void _reverseAD( + const Eigen::Matrix & dFdT, + JacobianMap& jacobians) const { + derived().reverseAD(dFdT, jacobians); + } +#endif }; } // namespace internal diff --git a/gtsam_unstable/nonlinear/tests/testCallRecord.cpp b/gtsam_unstable/nonlinear/tests/testCallRecord.cpp index a4561b349..f0569151b 100644 --- a/gtsam_unstable/nonlinear/tests/testCallRecord.cpp +++ b/gtsam_unstable/nonlinear/tests/testCallRecord.cpp @@ -90,7 +90,7 @@ struct Record: public internal::CallRecordImplementor { } template - friend struct internal::ReverseADImplementor; + friend struct internal::CallRecordImplementor; }; JacobianMap & NJM= *static_cast(NULL); From 7989a8c0dcda6cf3e554fff72dbed3c56f33c023 Mon Sep 17 00:00:00 2001 From: dellaert Date: Sat, 29 Nov 2014 13:08:10 +0100 Subject: [PATCH 009/126] Added wide test --- .../nonlinear/tests/testExpressionFactor.cpp | 35 +++++++++++++++++++ 1 file changed, 35 insertions(+) diff --git a/gtsam_unstable/nonlinear/tests/testExpressionFactor.cpp b/gtsam_unstable/nonlinear/tests/testExpressionFactor.cpp index d146ea945..09cad558a 100644 --- a/gtsam_unstable/nonlinear/tests/testExpressionFactor.cpp +++ b/gtsam_unstable/nonlinear/tests/testExpressionFactor.cpp @@ -76,10 +76,13 @@ TEST(ExpressionFactor, Model) { // Concise version ExpressionFactor f(model, Point2(0, 0), p); + + // Check values and derivatives EXPECT_DOUBLES_EQUAL(old.error(values), f.error(values), 1e-9); EXPECT_LONGS_EQUAL(2, f.dim()); boost::shared_ptr gf2 = f.linearize(values); EXPECT( assert_equal(*old.linearize(values), *gf2, 1e-9)); + EXPECT_CORRECT_FACTOR_JACOBIANS(f, values, 1e-5, 1e-5); // another way } /* ************************************************************************* */ @@ -124,6 +127,38 @@ TEST(ExpressionFactor, Unary) { EXPECT( assert_equal(expected, *jf, 1e-9)); } +/* ************************************************************************* */ +// Unary(Leaf)) and Unary(Unary(Leaf))) +// wide version (not handled in fixed-size pipeline) +typedef Eigen::Matrix Matrix93; +Vector9 wide(const Point3& p, boost::optional H) { + Vector9 v; + v << p.vector(), p.vector(), p.vector(); + if (H) *H << eye(3), eye(3), eye(3); + return v; +} +typedef Eigen::Matrix Matrix9; +Vector9 id9(const Vector9& v, boost::optional H) { + if (H) *H = Matrix9::Identity(); + return v; +} +TEST(ExpressionFactor, Wide) { + // Create some values + Values values; + values.insert(2, Point3(0, 0, 1)); + Point3_ point(2); + Vector9 measured; + Expression expression(wide,point); + SharedNoiseModel model = noiseModel::Unit::Create(9); + + ExpressionFactor f1(model, measured, expression); + EXPECT_CORRECT_FACTOR_JACOBIANS(f1, values, 1e-5, 1e-9); + + Expression expression2(id9,expression); + ExpressionFactor f2(model, measured, expression2); + EXPECT_CORRECT_FACTOR_JACOBIANS(f2, values, 1e-5, 1e-9); +} + /* ************************************************************************* */ static Point2 myUncal(const Cal3_S2& K, const Point2& p, boost::optional Dcal, boost::optional Dp) { From e2e29dac68e8bee98e1b99da925eaefa1237e52e Mon Sep 17 00:00:00 2001 From: dellaert Date: Sat, 29 Nov 2014 13:09:17 +0100 Subject: [PATCH 010/126] Removed #ifdef blocks and documented the AD process by numbering the methods in the order they are called --- gtsam/nonlinear/Expression-inl.h | 53 ++++--- gtsam/nonlinear/Expression.h | 2 +- gtsam_unstable/nonlinear/CallRecord.h | 137 ++++++++---------- .../nonlinear/tests/testCallRecord.cpp | 50 +++---- 4 files changed, 116 insertions(+), 126 deletions(-) diff --git a/gtsam/nonlinear/Expression-inl.h b/gtsam/nonlinear/Expression-inl.h index 08dd18ee3..332c23ca7 100644 --- a/gtsam/nonlinear/Expression-inl.h +++ b/gtsam/nonlinear/Expression-inl.h @@ -106,7 +106,7 @@ struct UseBlockIf { }; } -/// Handle Leaf Case: reverseAD ends here, by writing a matrix into Jacobians +/// Handle Leaf Case: reverse AD ends here, by writing a matrix into Jacobians template void handleLeafCase(const Eigen::MatrixBase& dTdA, JacobianMap& jacobians, Key key) { @@ -186,28 +186,28 @@ public: } } /** - * *** This is the main entry point for reverseAD, called from Expression *** + * *** This is the main entry point for reverse AD, called from Expression *** * Called only once, either inserts I into Jacobians (Leaf) or starts AD (Function) */ typedef Eigen::Matrix JacobianTT; - void startReverseAD(JacobianMap& jacobians) const { + void startReverseAD1(JacobianMap& jacobians) const { if (kind == Leaf) { // This branch will only be called on trivial Leaf expressions, i.e. Priors static const JacobianTT I = JacobianTT::Identity(); handleLeafCase(I, jacobians, content.key); } else if (kind == Function) // This is the more typical entry point, starting the AD pipeline - // Inside the startReverseAD that the correctly dimensioned pipeline is chosen. - content.ptr->startReverseAD(jacobians); + // Inside startReverseAD2 the correctly dimensioned pipeline is chosen. + content.ptr->startReverseAD2(jacobians); } // Either add to Jacobians (Leaf) or propagate (Function) template - void reverseAD(const Eigen::MatrixBase & dTdA, + void reverseAD1(const Eigen::MatrixBase & dTdA, JacobianMap& jacobians) const { if (kind == Leaf) handleLeafCase(dTdA, jacobians, content.key); else if (kind == Function) - content.ptr->reverseAD(dTdA, jacobians); + content.ptr->reverseAD2(dTdA, jacobians); } /// Define type so we can apply it as a meta-function @@ -470,10 +470,10 @@ struct FunctionalBase: ExpressionNode { struct Record { void print(const std::string& indent) const { } - void startReverseAD(JacobianMap& jacobians) const { + void startReverseAD4(JacobianMap& jacobians) const { } template - void reverseAD(const SomeMatrix & dFdT, JacobianMap& jacobians) const { + void reverseAD4(const SomeMatrix & dFdT, JacobianMap& jacobians) const { } }; /// Construct an execution trace for reverse AD @@ -505,9 +505,9 @@ struct JacobianTrace { typename Jacobian::type dTdA; }; -/** - * Recursive Definition of Functional ExpressionNode - */ +// Recursive Definition of Functional ExpressionNode +// The reason we inherit from Argument is because we can then +// case to this unique signature to retrieve the expression at any level template struct GenerateFunctionalNode: Argument, Base { @@ -528,7 +528,9 @@ struct GenerateFunctionalNode: Argument, Base { This::expression->dims(map); } - /// Recursive Record Class for Functional Expressions + // Recursive Record Class for Functional Expressions + // The reason we inherit from JacobianTrace is because we can then + // case to this unique signature to retrieve the value/trace at any level struct Record: JacobianTrace, Base::Record { typedef T return_type; @@ -543,17 +545,26 @@ struct GenerateFunctionalNode: Argument, Base { } /// Start the reverse AD process - void startReverseAD(JacobianMap& jacobians) const { - Base::Record::startReverseAD(jacobians); - This::trace.reverseAD(This::dTdA, jacobians); + void startReverseAD4(JacobianMap& jacobians) const { + Base::Record::startReverseAD4(jacobians); + // This is the crucial point where the size of the AD pipeline is selected. + // One pipeline is started for each argument, but the number of rows in each + // pipeline is the same, namely the dimension of the output argument T. + // For example, if the entire expression is rooted by a binary function + // yielding a 2D result, then the matrix dTdA will have 2 rows. + // ExecutionTrace::reverseAD1 just passes this on to CallRecord::reverseAD2 + // which calls the correctly sized CallRecord::reverseAD3, which in turn + // calls reverseAD4 below. + This::trace.reverseAD1(This::dTdA, jacobians); } /// Given df/dT, multiply in dT/dA and continue reverse AD process + // Cols is always known at compile time template - void reverseAD(const Eigen::Matrix & dFdT, + void reverseAD4(const Eigen::Matrix & dFdT, JacobianMap& jacobians) const { - Base::Record::reverseAD(dFdT, jacobians); - This::trace.reverseAD(dFdT * This::dTdA, jacobians); + Base::Record::reverseAD4(dFdT, jacobians); + This::trace.reverseAD1(dFdT * This::dTdA, jacobians); } }; @@ -614,8 +625,8 @@ struct FunctionalNode { struct Record: public internal::CallRecordImplementor::value>, public Base::Record { using Base::Record::print; - using Base::Record::startReverseAD; - using Base::Record::reverseAD; + using Base::Record::startReverseAD4; + using Base::Record::reverseAD4; virtual ~Record() { } diff --git a/gtsam/nonlinear/Expression.h b/gtsam/nonlinear/Expression.h index d44d21cd7..c7f022724 100644 --- a/gtsam/nonlinear/Expression.h +++ b/gtsam/nonlinear/Expression.h @@ -209,7 +209,7 @@ private: ExecutionTraceStorage traceStorage[size]; ExecutionTrace trace; T value(traceExecution(values, trace, traceStorage)); - trace.startReverseAD(jacobians); + trace.startReverseAD1(jacobians); return value; } diff --git a/gtsam_unstable/nonlinear/CallRecord.h b/gtsam_unstable/nonlinear/CallRecord.h index 5a1fdadc4..53eb7e845 100644 --- a/gtsam_unstable/nonlinear/CallRecord.h +++ b/gtsam_unstable/nonlinear/CallRecord.h @@ -32,12 +32,6 @@ class JacobianMap; // forward declaration //----------------------------------------------------------------------------- -/** - * MaxVirtualStaticRows defines how many separate virtual reverseAD with specific - * static rows (1..MaxVirtualStaticRows) methods will be part of the CallRecord interface. - */ -#define MaxVirtualStaticRows 4 - namespace internal { /** @@ -57,7 +51,8 @@ struct ConvertToVirtualFunctionSupportedMatrixType { template<> struct ConvertToVirtualFunctionSupportedMatrixType { template - static const Eigen::Matrix convert( + static const Eigen::Matrix convert( const Eigen::MatrixBase & x) { return x; } @@ -72,73 +67,68 @@ struct ConvertToVirtualFunctionSupportedMatrixType { } // namespace internal /** - * The CallRecord class stores the Jacobians of applying a function - * with respect to each of its arguments. It also stores an execution trace - * (defined below) for each of its arguments. - * - * It is implemented in the function-style ExpressionNode's nested Record class below. + * The CallRecord is an abstract base class for the any class that stores + * the Jacobians of applying a function with respect to each of its arguments, + * as well as an execution trace for each of its arguments. */ template struct CallRecord { + + // Print entire record, recursively inline void print(const std::string& indent) const { _print(indent); } - inline void startReverseAD(JacobianMap& jacobians) const { - _startReverseAD(jacobians); + // Main entry point for the reverse AD process of a functional expression. + // Called *once* by the main AD entry point, ExecutionTrace::startReverseAD1 + // This function then calls ExecutionTrace::reverseAD for every argument + // which will in turn call the reverseAD method below. + // This non-virtual function _startReverseAD3, implemented in derived + inline void startReverseAD2(JacobianMap& jacobians) const { + _startReverseAD3(jacobians); } + // Dispatch the reverseAD2 calls issued by ExecutionTrace::reverseAD1 + // Here we convert to dynamic if the template - inline void reverseAD(const Eigen::MatrixBase & dFdT, + inline void reverseAD2(const Eigen::MatrixBase & dFdT, JacobianMap& jacobians) const { - _reverseAD( - internal::ConvertToVirtualFunctionSupportedMatrixType< - (Derived::RowsAtCompileTime > MaxVirtualStaticRows) - >::convert(dFdT), - jacobians - ); + _reverseAD3( + internal::ConvertToVirtualFunctionSupportedMatrixType< + (Derived::RowsAtCompileTime > 5)>::convert(dFdT), + jacobians); } - inline void reverseAD(const Matrix & dFdT, JacobianMap& jacobians) const { - _reverseAD(dFdT, jacobians); - } +// TODO: remove once Hannes agrees this is never called as handled by above +// inline void reverseAD2(const Matrix & dFdT, JacobianMap& jacobians) const { +// _reverseAD3(dFdT, jacobians); +// } virtual ~CallRecord() { } private: - virtual void _print(const std::string& indent) const = 0; - virtual void _startReverseAD(JacobianMap& jacobians) const = 0; - virtual void _reverseAD(const Matrix & dFdT, JacobianMap& jacobians) const = 0; - virtual void _reverseAD( + virtual void _print(const std::string& indent) const = 0; + virtual void _startReverseAD3(JacobianMap& jacobians) const = 0; + + virtual void _reverseAD3(const Matrix & dFdT, + JacobianMap& jacobians) const = 0; + + virtual void _reverseAD3( const Eigen::Matrix & dFdT, JacobianMap& jacobians) const = 0; -#if MaxVirtualStaticRows >= 1 - virtual void _reverseAD( - const Eigen::Matrix & dFdT, + + virtual void _reverseAD3(const Eigen::Matrix & dFdT, JacobianMap& jacobians) const = 0; -#endif -#if MaxVirtualStaticRows >= 2 - virtual void _reverseAD( - const Eigen::Matrix & dFdT, + virtual void _reverseAD3(const Eigen::Matrix & dFdT, JacobianMap& jacobians) const = 0; -#endif -#if MaxVirtualStaticRows >= 3 - virtual void _reverseAD( - const Eigen::Matrix & dFdT, + virtual void _reverseAD3(const Eigen::Matrix & dFdT, JacobianMap& jacobians) const = 0; -#endif -#if MaxVirtualStaticRows >= 4 - virtual void _reverseAD( - const Eigen::Matrix & dFdT, + virtual void _reverseAD3(const Eigen::Matrix & dFdT, JacobianMap& jacobians) const = 0; -#endif -#if MaxVirtualStaticRows >= 5 - virtual void _reverseAD( - const Eigen::Matrix & dFdT, + virtual void _reverseAD3(const Eigen::Matrix & dFdT, JacobianMap& jacobians) const = 0; -#endif }; namespace internal { @@ -149,59 +139,48 @@ namespace internal { template struct CallRecordImplementor: public CallRecord { private: + const Derived & derived() const { return static_cast(*this); } + virtual void _print(const std::string& indent) const { derived().print(indent); } - virtual void _startReverseAD(JacobianMap& jacobians) const { - derived().startReverseAD(jacobians); + + virtual void _startReverseAD3(JacobianMap& jacobians) const { + derived().startReverseAD4(jacobians); } - virtual void _reverseAD(const Matrix & dFdT, JacobianMap& jacobians) const { - derived().reverseAD(dFdT, jacobians); + virtual void _reverseAD3(const Matrix & dFdT, JacobianMap& jacobians) const { + derived().reverseAD4(dFdT, jacobians); } - virtual void _reverseAD( + + virtual void _reverseAD3( const Eigen::Matrix & dFdT, JacobianMap& jacobians) const { - derived().reverseAD(dFdT, jacobians); + derived().reverseAD4(dFdT, jacobians); } -#if MaxVirtualStaticRows >= 1 - virtual void _reverseAD( - const Eigen::Matrix & dFdT, + virtual void _reverseAD3(const Eigen::Matrix & dFdT, JacobianMap& jacobians) const { - derived().reverseAD(dFdT, jacobians); + derived().reverseAD4(dFdT, jacobians); } -#endif -#if MaxVirtualStaticRows >= 2 - virtual void _reverseAD( - const Eigen::Matrix & dFdT, + virtual void _reverseAD3(const Eigen::Matrix & dFdT, JacobianMap& jacobians) const { - derived().reverseAD(dFdT, jacobians); + derived().reverseAD4(dFdT, jacobians); } -#endif -#if MaxVirtualStaticRows >= 3 - virtual void _reverseAD( - const Eigen::Matrix & dFdT, + virtual void _reverseAD3(const Eigen::Matrix & dFdT, JacobianMap& jacobians) const { - derived().reverseAD(dFdT, jacobians); + derived().reverseAD4(dFdT, jacobians); } -#endif -#if MaxVirtualStaticRows >= 4 - virtual void _reverseAD( - const Eigen::Matrix & dFdT, + virtual void _reverseAD3(const Eigen::Matrix & dFdT, JacobianMap& jacobians) const { - derived().reverseAD(dFdT, jacobians); + derived().reverseAD4(dFdT, jacobians); } -#endif -#if MaxVirtualStaticRows >= 5 - virtual void _reverseAD( - const Eigen::Matrix & dFdT, + virtual void _reverseAD3(const Eigen::Matrix & dFdT, JacobianMap& jacobians) const { - derived().reverseAD(dFdT, jacobians); + derived().reverseAD4(dFdT, jacobians); } -#endif }; } // namespace internal diff --git a/gtsam_unstable/nonlinear/tests/testCallRecord.cpp b/gtsam_unstable/nonlinear/tests/testCallRecord.cpp index f0569151b..057a870d5 100644 --- a/gtsam_unstable/nonlinear/tests/testCallRecord.cpp +++ b/gtsam_unstable/nonlinear/tests/testCallRecord.cpp @@ -33,7 +33,7 @@ static const int Cols = 3; int dynamicIfAboveMax(int i){ - if(i > MaxVirtualStaticRows){ + if(i > 5){ return Eigen::Dynamic; } else return i; @@ -76,20 +76,20 @@ struct Record: public internal::CallRecordImplementor { } void print(const std::string& indent) const { } - void startReverseAD(JacobianMap& jacobians) const { + void startReverseAD4(JacobianMap& jacobians) const { } mutable CallConfig cc; private: template - void reverseAD(const SomeMatrix & dFdT, JacobianMap& jacobians) const { + void reverseAD4(const SomeMatrix & dFdT, JacobianMap& jacobians) const { cc.compTimeRows = SomeMatrix::RowsAtCompileTime; cc.compTimeCols = SomeMatrix::ColsAtCompileTime; cc.runTimeRows = dFdT.rows(); cc.runTimeCols = dFdT.cols(); } - template + template friend struct internal::CallRecordImplementor; }; @@ -102,56 +102,56 @@ TEST(CallRecord, virtualReverseAdDispatching) { Record record; { const int Rows = 1; - record.CallRecord::reverseAD(Eigen::Matrix(), NJM); + record.CallRecord::reverseAD2(Eigen::Matrix(), NJM); EXPECT((assert_equal(record.cc, CallConfig(Rows, Cols)))); - record.CallRecord::reverseAD(DynRowMat(Rows, Cols), NJM); + record.CallRecord::reverseAD2(DynRowMat(Rows, Cols), NJM); EXPECT((assert_equal(record.cc, CallConfig(Eigen::Dynamic, Cols, Rows, Cols)))); - record.CallRecord::reverseAD(Eigen::MatrixXd(Rows, Cols), NJM); + record.CallRecord::reverseAD2(Eigen::MatrixXd(Rows, Cols), NJM); EXPECT((assert_equal(record.cc, CallConfig(Eigen::Dynamic, Eigen::Dynamic, Rows, Cols)))); } { const int Rows = 2; - record.CallRecord::reverseAD(Eigen::Matrix(), NJM); + record.CallRecord::reverseAD2(Eigen::Matrix(), NJM); EXPECT((assert_equal(record.cc, CallConfig(Rows, Cols)))); - record.CallRecord::reverseAD(DynRowMat(Rows, Cols), NJM); + record.CallRecord::reverseAD2(DynRowMat(Rows, Cols), NJM); EXPECT((assert_equal(record.cc, CallConfig(Eigen::Dynamic, Cols, Rows, Cols)))); - record.CallRecord::reverseAD(Eigen::MatrixXd(Rows, Cols), NJM); + record.CallRecord::reverseAD2(Eigen::MatrixXd(Rows, Cols), NJM); EXPECT((assert_equal(record.cc, CallConfig(Eigen::Dynamic, Eigen::Dynamic, Rows, Cols)))); } { const int Rows = 3; - record.CallRecord::reverseAD(Eigen::Matrix(), NJM); + record.CallRecord::reverseAD2(Eigen::Matrix(), NJM); EXPECT((assert_equal(record.cc, CallConfig(Rows, Cols)))); - record.CallRecord::reverseAD(DynRowMat(Rows, Cols), NJM); + record.CallRecord::reverseAD2(DynRowMat(Rows, Cols), NJM); EXPECT((assert_equal(record.cc, CallConfig(Eigen::Dynamic, Cols, Rows, Cols)))); - record.CallRecord::reverseAD(Eigen::MatrixXd(Rows, Cols), NJM); + record.CallRecord::reverseAD2(Eigen::MatrixXd(Rows, Cols), NJM); EXPECT((assert_equal(record.cc, CallConfig(Eigen::Dynamic, Eigen::Dynamic, Rows, Cols)))); } { - const int Rows = MaxVirtualStaticRows; - record.CallRecord::reverseAD(Eigen::Matrix(), NJM); + const int Rows = 4; + record.CallRecord::reverseAD2(Eigen::Matrix(), NJM); EXPECT((assert_equal(record.cc, CallConfig(Rows, Cols)))); - record.CallRecord::reverseAD(DynRowMat(Rows, Cols), NJM); + record.CallRecord::reverseAD2(DynRowMat(Rows, Cols), NJM); EXPECT((assert_equal(record.cc, CallConfig(Eigen::Dynamic, Cols, Rows, Cols)))); - record.CallRecord::reverseAD(Eigen::MatrixXd(Rows, Cols), NJM); + record.CallRecord::reverseAD2(Eigen::MatrixXd(Rows, Cols), NJM); EXPECT((assert_equal(record.cc, CallConfig(Eigen::Dynamic, Eigen::Dynamic, Rows, Cols)))); } { - const int Rows = MaxVirtualStaticRows + 1; - record.CallRecord::reverseAD(Eigen::Matrix(), NJM); + const int Rows = 5; + record.CallRecord::reverseAD2(Eigen::Matrix(), NJM); EXPECT((assert_equal(record.cc, CallConfig(Rows, Cols)))); - record.CallRecord::reverseAD(DynRowMat(Rows, Cols), NJM); + record.CallRecord::reverseAD2(DynRowMat(Rows, Cols), NJM); EXPECT((assert_equal(record.cc, CallConfig(Eigen::Dynamic, Cols, Rows, Cols)))); - record.CallRecord::reverseAD(Eigen::MatrixXd(Rows, Cols), NJM); + record.CallRecord::reverseAD2(Eigen::MatrixXd(Rows, Cols), NJM); EXPECT((assert_equal(record.cc, CallConfig(Eigen::Dynamic, Eigen::Dynamic, Rows, Cols)))); } { - const int Rows = MaxVirtualStaticRows + 2; - record.CallRecord::reverseAD(Eigen::Matrix(), NJM); + const int Rows = 6; + record.CallRecord::reverseAD2(Eigen::Matrix(), NJM); EXPECT((assert_equal(record.cc, CallConfig(Rows, Cols)))); - record.CallRecord::reverseAD(DynRowMat(Rows, Cols), NJM); + record.CallRecord::reverseAD2(DynRowMat(Rows, Cols), NJM); EXPECT((assert_equal(record.cc, CallConfig(Eigen::Dynamic, Cols, Rows, Cols)))); - record.CallRecord::reverseAD(Eigen::MatrixXd(Rows, Cols), NJM); + record.CallRecord::reverseAD2(Eigen::MatrixXd(Rows, Cols), NJM); EXPECT((assert_equal(record.cc, CallConfig(Eigen::Dynamic, Eigen::Dynamic, Rows, Cols)))); } } From be00e1c34843f0ad10067f7804779cbe709bbe68 Mon Sep 17 00:00:00 2001 From: dellaert Date: Sat, 29 Nov 2014 13:44:49 +0100 Subject: [PATCH 011/126] Allow Vector and Matrix in list of template values --- wrap/Method.cpp | 2 +- wrap/Module.cpp | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/wrap/Method.cpp b/wrap/Method.cpp index 49d90378d..1feb0f70f 100644 --- a/wrap/Method.cpp +++ b/wrap/Method.cpp @@ -58,7 +58,7 @@ string Method::wrapper_call(FileWriter& wrapperFile, Str cppClassName, // check arguments // extra argument obj -> nargin-1 is passed ! // example: checkArguments("equals",nargout,nargin-1,2); - wrapperFile.oss << " checkArguments(\"" << name_ << "\",nargout,nargin-1," + wrapperFile.oss << " checkArguments(\"" << matlabName() << "\",nargout,nargin-1," << args.size() << ");\n"; // get class pointer diff --git a/wrap/Module.cpp b/wrap/Module.cpp index ac0e0a579..ee1e78742 100644 --- a/wrap/Module.cpp +++ b/wrap/Module.cpp @@ -162,7 +162,7 @@ void Module::parseMarkup(const std::string& data) { vector templateArgValues; Rule templateArgValue_p = (*(namespace_name_p[push_back_a(templateArgValue.namespaces)] >> str_p("::")) >> - className_p[assign_a(templateArgValue.name)]) + (className_p | eigenType_p)[assign_a(templateArgValue.name)]) [push_back_a(templateArgValues, templateArgValue)] [clear_a(templateArgValue)]; From 5ab9b8e439120d24ea33ab9022de2dad49b4f238 Mon Sep 17 00:00:00 2001 From: dellaert Date: Sat, 29 Nov 2014 13:45:11 +0100 Subject: [PATCH 012/126] Test Vector and Matrix as template values --- .../tests/expected-python/geometry_python.cpp | 4 + wrap/tests/expected2/MyFactorPosePoint2.m | 6 +- wrap/tests/expected2/MyTemplatePoint2.m | 26 +++- wrap/tests/expected2/MyTemplatePoint3.m | 48 +++++-- wrap/tests/expected2/aGlobalFunction.m | 2 +- wrap/tests/expected2/geometry_wrapper.cpp | 136 ++++++++++++------ .../expected2/overloadedGlobalFunction.m | 4 +- wrap/tests/geometry.h | 2 +- 8 files changed, 162 insertions(+), 66 deletions(-) diff --git a/wrap/tests/expected-python/geometry_python.cpp b/wrap/tests/expected-python/geometry_python.cpp index f500f2984..b28e69709 100644 --- a/wrap/tests/expected-python/geometry_python.cpp +++ b/wrap/tests/expected-python/geometry_python.cpp @@ -59,6 +59,8 @@ class_("MyTemplatePoint2") .def("return_ptrs", &MyTemplatePoint2::return_ptrs); .def("templatedMethod", &MyTemplatePoint2::templatedMethod); .def("templatedMethod", &MyTemplatePoint2::templatedMethod); + .def("templatedMethod", &MyTemplatePoint2::templatedMethod); + .def("templatedMethod", &MyTemplatePoint2::templatedMethod); ; class_("MyTemplatePoint3") @@ -72,6 +74,8 @@ class_("MyTemplatePoint3") .def("return_ptrs", &MyTemplatePoint3::return_ptrs); .def("templatedMethod", &MyTemplatePoint3::templatedMethod); .def("templatedMethod", &MyTemplatePoint3::templatedMethod); + .def("templatedMethod", &MyTemplatePoint3::templatedMethod); + .def("templatedMethod", &MyTemplatePoint3::templatedMethod); ; class_("MyFactorPosePoint2") diff --git a/wrap/tests/expected2/MyFactorPosePoint2.m b/wrap/tests/expected2/MyFactorPosePoint2.m index 166e1514d..e55386cc0 100644 --- a/wrap/tests/expected2/MyFactorPosePoint2.m +++ b/wrap/tests/expected2/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(69, my_ptr); + geometry_wrapper(73, 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(70, varargin{1}, varargin{2}, varargin{3}, varargin{4}); + my_ptr = geometry_wrapper(74, 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(71, obj.ptr_MyFactorPosePoint2); + geometry_wrapper(75, obj.ptr_MyFactorPosePoint2); end function display(obj), obj.print(''); end diff --git a/wrap/tests/expected2/MyTemplatePoint2.m b/wrap/tests/expected2/MyTemplatePoint2.m index 5f1c69480..9df4d2d1a 100644 --- a/wrap/tests/expected2/MyTemplatePoint2.m +++ b/wrap/tests/expected2/MyTemplatePoint2.m @@ -12,8 +12,10 @@ %return_T(Point2 value) : returns gtsam::Point2 %return_Tptr(Point2 value) : returns gtsam::Point2 %return_ptrs(Point2 p1, Point2 p2) : returns pair< gtsam::Point2, gtsam::Point2 > +%templatedMethodMatrix(Matrix t) : returns void %templatedMethodPoint2(Point2 t) : returns void %templatedMethodPoint3(Point3 t) : returns void +%templatedMethodVector(Vector t) : returns void % classdef MyTemplatePoint2 < MyBase properties @@ -107,11 +109,21 @@ classdef MyTemplatePoint2 < MyBase end end + function varargout = templatedMethodMatrix(this, varargin) + % TEMPLATEDMETHODMATRIX usage: templatedMethodMatrix(Matrix t) : returns void + % 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') + geometry_wrapper(54, this, varargin{:}); + else + error('Arguments do not match any overload of function MyTemplatePoint2.templatedMethod'); + end + end + function varargout = templatedMethodPoint2(this, varargin) % TEMPLATEDMETHODPOINT2 usage: templatedMethodPoint2(Point2 t) : returns void % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html if length(varargin) == 1 && isa(varargin{1},'gtsam.Point2') - geometry_wrapper(54, this, varargin{:}); + geometry_wrapper(55, this, varargin{:}); else error('Arguments do not match any overload of function MyTemplatePoint2.templatedMethod'); end @@ -121,7 +133,17 @@ classdef MyTemplatePoint2 < MyBase % TEMPLATEDMETHODPOINT3 usage: templatedMethodPoint3(Point3 t) : returns void % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html if length(varargin) == 1 && isa(varargin{1},'gtsam.Point3') - geometry_wrapper(55, this, varargin{:}); + geometry_wrapper(56, this, varargin{:}); + else + error('Arguments do not match any overload of function MyTemplatePoint2.templatedMethod'); + end + end + + function varargout = templatedMethodVector(this, varargin) + % TEMPLATEDMETHODVECTOR usage: templatedMethodVector(Vector t) : returns void + % 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') + geometry_wrapper(57, this, varargin{:}); else error('Arguments do not match any overload of function MyTemplatePoint2.templatedMethod'); end diff --git a/wrap/tests/expected2/MyTemplatePoint3.m b/wrap/tests/expected2/MyTemplatePoint3.m index 848e224fd..274768d3a 100644 --- a/wrap/tests/expected2/MyTemplatePoint3.m +++ b/wrap/tests/expected2/MyTemplatePoint3.m @@ -12,8 +12,10 @@ %return_T(Point3 value) : returns gtsam::Point3 %return_Tptr(Point3 value) : returns gtsam::Point3 %return_ptrs(Point3 p1, Point3 p2) : returns pair< gtsam::Point3, gtsam::Point3 > +%templatedMethodMatrix(Matrix t) : returns void %templatedMethodPoint2(Point2 t) : returns void %templatedMethodPoint3(Point3 t) : returns void +%templatedMethodVector(Vector t) : returns void % classdef MyTemplatePoint3 < MyBase properties @@ -25,11 +27,11 @@ classdef MyTemplatePoint3 < MyBase if nargin == 2 my_ptr = varargin{2}; else - my_ptr = geometry_wrapper(57, varargin{2}); + my_ptr = geometry_wrapper(59, varargin{2}); end - base_ptr = geometry_wrapper(56, my_ptr); + base_ptr = geometry_wrapper(58, my_ptr); elseif nargin == 0 - [ my_ptr, base_ptr ] = geometry_wrapper(58); + [ my_ptr, base_ptr ] = geometry_wrapper(60); else error('Arguments do not match any overload of MyTemplatePoint3 constructor'); end @@ -38,7 +40,7 @@ classdef MyTemplatePoint3 < MyBase end function delete(obj) - geometry_wrapper(59, obj.ptr_MyTemplatePoint3); + geometry_wrapper(61, obj.ptr_MyTemplatePoint3); end function display(obj), obj.print(''); end @@ -49,7 +51,7 @@ classdef MyTemplatePoint3 < MyBase % ACCEPT_T usage: accept_T(Point3 value) : returns void % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html if length(varargin) == 1 && isa(varargin{1},'gtsam.Point3') - geometry_wrapper(60, this, varargin{:}); + geometry_wrapper(62, this, varargin{:}); else error('Arguments do not match any overload of function MyTemplatePoint3.accept_T'); end @@ -59,7 +61,7 @@ classdef MyTemplatePoint3 < MyBase % ACCEPT_TPTR usage: accept_Tptr(Point3 value) : returns void % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html if length(varargin) == 1 && isa(varargin{1},'gtsam.Point3') - geometry_wrapper(61, this, varargin{:}); + geometry_wrapper(63, this, varargin{:}); else error('Arguments do not match any overload of function MyTemplatePoint3.accept_Tptr'); end @@ -68,20 +70,20 @@ classdef MyTemplatePoint3 < MyBase function varargout = create_MixedPtrs(this, varargin) % CREATE_MIXEDPTRS usage: create_MixedPtrs() : returns pair< gtsam::Point3, gtsam::Point3 > % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html - [ varargout{1} varargout{2} ] = geometry_wrapper(62, this, varargin{:}); + [ varargout{1} varargout{2} ] = geometry_wrapper(64, this, varargin{:}); end function varargout = create_ptrs(this, varargin) % CREATE_PTRS usage: create_ptrs() : returns pair< gtsam::Point3, gtsam::Point3 > % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html - [ varargout{1} varargout{2} ] = geometry_wrapper(63, this, varargin{:}); + [ varargout{1} varargout{2} ] = geometry_wrapper(65, this, varargin{:}); end function varargout = return_T(this, varargin) % RETURN_T usage: return_T(Point3 value) : returns gtsam::Point3 % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html if length(varargin) == 1 && isa(varargin{1},'gtsam.Point3') - varargout{1} = geometry_wrapper(64, this, varargin{:}); + varargout{1} = geometry_wrapper(66, this, varargin{:}); else error('Arguments do not match any overload of function MyTemplatePoint3.return_T'); end @@ -91,7 +93,7 @@ classdef MyTemplatePoint3 < MyBase % RETURN_TPTR usage: return_Tptr(Point3 value) : returns gtsam::Point3 % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html if length(varargin) == 1 && isa(varargin{1},'gtsam.Point3') - varargout{1} = geometry_wrapper(65, this, varargin{:}); + varargout{1} = geometry_wrapper(67, this, varargin{:}); else error('Arguments do not match any overload of function MyTemplatePoint3.return_Tptr'); end @@ -101,17 +103,27 @@ classdef MyTemplatePoint3 < MyBase % RETURN_PTRS usage: return_ptrs(Point3 p1, Point3 p2) : returns pair< gtsam::Point3, gtsam::Point3 > % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html if length(varargin) == 2 && isa(varargin{1},'gtsam.Point3') && isa(varargin{2},'gtsam.Point3') - [ varargout{1} varargout{2} ] = geometry_wrapper(66, this, varargin{:}); + [ varargout{1} varargout{2} ] = geometry_wrapper(68, this, varargin{:}); else error('Arguments do not match any overload of function MyTemplatePoint3.return_ptrs'); end end + function varargout = templatedMethodMatrix(this, varargin) + % TEMPLATEDMETHODMATRIX usage: templatedMethodMatrix(Matrix t) : returns void + % 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') + geometry_wrapper(69, this, varargin{:}); + else + error('Arguments do not match any overload of function MyTemplatePoint3.templatedMethod'); + end + end + function varargout = templatedMethodPoint2(this, varargin) % TEMPLATEDMETHODPOINT2 usage: templatedMethodPoint2(Point2 t) : returns void % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html if length(varargin) == 1 && isa(varargin{1},'gtsam.Point2') - geometry_wrapper(67, this, varargin{:}); + geometry_wrapper(70, this, varargin{:}); else error('Arguments do not match any overload of function MyTemplatePoint3.templatedMethod'); end @@ -121,7 +133,17 @@ classdef MyTemplatePoint3 < MyBase % TEMPLATEDMETHODPOINT3 usage: templatedMethodPoint3(Point3 t) : returns void % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html if length(varargin) == 1 && isa(varargin{1},'gtsam.Point3') - geometry_wrapper(68, this, varargin{:}); + geometry_wrapper(71, this, varargin{:}); + else + error('Arguments do not match any overload of function MyTemplatePoint3.templatedMethod'); + end + end + + function varargout = templatedMethodVector(this, varargin) + % TEMPLATEDMETHODVECTOR usage: templatedMethodVector(Vector t) : returns void + % 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') + geometry_wrapper(72, this, varargin{:}); else error('Arguments do not match any overload of function MyTemplatePoint3.templatedMethod'); end diff --git a/wrap/tests/expected2/aGlobalFunction.m b/wrap/tests/expected2/aGlobalFunction.m index 5cf9aafa1..e000338b6 100644 --- a/wrap/tests/expected2/aGlobalFunction.m +++ b/wrap/tests/expected2/aGlobalFunction.m @@ -1,6 +1,6 @@ function varargout = aGlobalFunction(varargin) if length(varargin) == 0 - varargout{1} = geometry_wrapper(72, varargin{:}); + varargout{1} = geometry_wrapper(76, varargin{:}); else error('Arguments do not match any overload of function aGlobalFunction'); end diff --git a/wrap/tests/expected2/geometry_wrapper.cpp b/wrap/tests/expected2/geometry_wrapper.cpp index ab6ae5aa7..77559f3da 100644 --- a/wrap/tests/expected2/geometry_wrapper.cpp +++ b/wrap/tests/expected2/geometry_wrapper.cpp @@ -667,22 +667,40 @@ void MyTemplatePoint2_return_ptrs_53(int nargout, mxArray *out[], int nargin, co void MyTemplatePoint2_templatedMethod_54(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr Shared; - checkArguments("templatedMethod",nargout,nargin-1,1); + checkArguments("templatedMethodMatrix",nargout,nargin-1,1); Shared obj = unwrap_shared_ptr(in[0], "ptr_MyTemplatePoint2"); - gtsam::Point2& t = *unwrap_shared_ptr< gtsam::Point2 >(in[1], "ptr_gtsamPoint2"); - obj->templatedMethod(t); + Matrix& t = *unwrap_shared_ptr< Matrix >(in[1], "ptr_Matrix"); + obj->templatedMethod(t); } void MyTemplatePoint2_templatedMethod_55(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr Shared; - checkArguments("templatedMethod",nargout,nargin-1,1); + checkArguments("templatedMethodPoint2",nargout,nargin-1,1); + Shared obj = unwrap_shared_ptr(in[0], "ptr_MyTemplatePoint2"); + gtsam::Point2& t = *unwrap_shared_ptr< gtsam::Point2 >(in[1], "ptr_gtsamPoint2"); + obj->templatedMethod(t); +} + +void MyTemplatePoint2_templatedMethod_56(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + typedef boost::shared_ptr Shared; + checkArguments("templatedMethodPoint3",nargout,nargin-1,1); Shared obj = unwrap_shared_ptr(in[0], "ptr_MyTemplatePoint2"); gtsam::Point3& t = *unwrap_shared_ptr< gtsam::Point3 >(in[1], "ptr_gtsamPoint3"); obj->templatedMethod(t); } -void MyTemplatePoint3_collectorInsertAndMakeBase_56(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void MyTemplatePoint2_templatedMethod_57(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + typedef boost::shared_ptr Shared; + checkArguments("templatedMethodVector",nargout,nargin-1,1); + Shared obj = unwrap_shared_ptr(in[0], "ptr_MyTemplatePoint2"); + Vector& t = *unwrap_shared_ptr< Vector >(in[1], "ptr_Vector"); + obj->templatedMethod(t); +} + +void MyTemplatePoint3_collectorInsertAndMakeBase_58(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { mexAtExit(&_deleteAllObjects); typedef boost::shared_ptr Shared; @@ -695,7 +713,7 @@ void MyTemplatePoint3_collectorInsertAndMakeBase_56(int nargout, mxArray *out[], *reinterpret_cast(mxGetData(out[0])) = new SharedBase(*self); } -void MyTemplatePoint3_upcastFromVoid_57(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { +void MyTemplatePoint3_upcastFromVoid_59(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])); @@ -704,7 +722,7 @@ void MyTemplatePoint3_upcastFromVoid_57(int nargout, mxArray *out[], int nargin, *reinterpret_cast(mxGetData(out[0])) = self; } -void MyTemplatePoint3_constructor_58(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void MyTemplatePoint3_constructor_60(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { mexAtExit(&_deleteAllObjects); typedef boost::shared_ptr Shared; @@ -719,7 +737,7 @@ void MyTemplatePoint3_constructor_58(int nargout, mxArray *out[], int nargin, co *reinterpret_cast(mxGetData(out[1])) = new SharedBase(*self); } -void MyTemplatePoint3_deconstructor_59(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void MyTemplatePoint3_deconstructor_61(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr Shared; checkArguments("delete_MyTemplatePoint3",nargout,nargin,1); @@ -732,7 +750,7 @@ void MyTemplatePoint3_deconstructor_59(int nargout, mxArray *out[], int nargin, } } -void MyTemplatePoint3_accept_T_60(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void MyTemplatePoint3_accept_T_62(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr Shared; checkArguments("accept_T",nargout,nargin-1,1); @@ -741,7 +759,7 @@ void MyTemplatePoint3_accept_T_60(int nargout, mxArray *out[], int nargin, const obj->accept_T(value); } -void MyTemplatePoint3_accept_Tptr_61(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void MyTemplatePoint3_accept_Tptr_63(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr Shared; checkArguments("accept_Tptr",nargout,nargin-1,1); @@ -750,7 +768,7 @@ void MyTemplatePoint3_accept_Tptr_61(int nargout, mxArray *out[], int nargin, co obj->accept_Tptr(value); } -void MyTemplatePoint3_create_MixedPtrs_62(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void MyTemplatePoint3_create_MixedPtrs_64(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr SharedPoint3; typedef boost::shared_ptr SharedPoint3; @@ -762,7 +780,7 @@ void MyTemplatePoint3_create_MixedPtrs_62(int nargout, mxArray *out[], int nargi out[1] = wrap_shared_ptr(pairResult.second,"gtsam.Point3", false); } -void MyTemplatePoint3_create_ptrs_63(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void MyTemplatePoint3_create_ptrs_65(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr SharedPoint3; typedef boost::shared_ptr SharedPoint3; @@ -774,7 +792,7 @@ void MyTemplatePoint3_create_ptrs_63(int nargout, mxArray *out[], int nargin, co out[1] = wrap_shared_ptr(pairResult.second,"gtsam.Point3", false); } -void MyTemplatePoint3_return_T_64(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void MyTemplatePoint3_return_T_66(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr SharedPoint3; typedef boost::shared_ptr Shared; @@ -784,7 +802,7 @@ void MyTemplatePoint3_return_T_64(int nargout, mxArray *out[], int nargin, const out[0] = wrap_shared_ptr(SharedPoint3(new gtsam::Point3(obj->return_T(value))),"gtsam.Point3", false); } -void MyTemplatePoint3_return_Tptr_65(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void MyTemplatePoint3_return_Tptr_67(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr SharedPoint3; typedef boost::shared_ptr Shared; @@ -794,7 +812,7 @@ void MyTemplatePoint3_return_Tptr_65(int nargout, mxArray *out[], int nargin, co out[0] = wrap_shared_ptr(obj->return_Tptr(value),"gtsam.Point3", false); } -void MyTemplatePoint3_return_ptrs_66(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void MyTemplatePoint3_return_ptrs_68(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr SharedPoint3; typedef boost::shared_ptr SharedPoint3; @@ -808,25 +826,43 @@ void MyTemplatePoint3_return_ptrs_66(int nargout, mxArray *out[], int nargin, co out[1] = wrap_shared_ptr(pairResult.second,"gtsam.Point3", false); } -void MyTemplatePoint3_templatedMethod_67(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void MyTemplatePoint3_templatedMethod_69(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr Shared; - checkArguments("templatedMethod",nargout,nargin-1,1); + checkArguments("templatedMethodMatrix",nargout,nargin-1,1); + Shared obj = unwrap_shared_ptr(in[0], "ptr_MyTemplatePoint3"); + Matrix& t = *unwrap_shared_ptr< Matrix >(in[1], "ptr_Matrix"); + obj->templatedMethod(t); +} + +void MyTemplatePoint3_templatedMethod_70(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + typedef boost::shared_ptr Shared; + checkArguments("templatedMethodPoint2",nargout,nargin-1,1); Shared obj = unwrap_shared_ptr(in[0], "ptr_MyTemplatePoint3"); gtsam::Point2& t = *unwrap_shared_ptr< gtsam::Point2 >(in[1], "ptr_gtsamPoint2"); obj->templatedMethod(t); } -void MyTemplatePoint3_templatedMethod_68(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void MyTemplatePoint3_templatedMethod_71(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr Shared; - checkArguments("templatedMethod",nargout,nargin-1,1); + checkArguments("templatedMethodPoint3",nargout,nargin-1,1); Shared obj = unwrap_shared_ptr(in[0], "ptr_MyTemplatePoint3"); gtsam::Point3& t = *unwrap_shared_ptr< gtsam::Point3 >(in[1], "ptr_gtsamPoint3"); obj->templatedMethod(t); } -void MyFactorPosePoint2_collectorInsertAndMakeBase_69(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void MyTemplatePoint3_templatedMethod_72(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + typedef boost::shared_ptr Shared; + checkArguments("templatedMethodVector",nargout,nargin-1,1); + Shared obj = unwrap_shared_ptr(in[0], "ptr_MyTemplatePoint3"); + Vector& t = *unwrap_shared_ptr< Vector >(in[1], "ptr_Vector"); + obj->templatedMethod(t); +} + +void MyFactorPosePoint2_collectorInsertAndMakeBase_73(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { mexAtExit(&_deleteAllObjects); typedef boost::shared_ptr Shared; @@ -835,7 +871,7 @@ void MyFactorPosePoint2_collectorInsertAndMakeBase_69(int nargout, mxArray *out[ collector_MyFactorPosePoint2.insert(self); } -void MyFactorPosePoint2_constructor_70(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void MyFactorPosePoint2_constructor_74(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { mexAtExit(&_deleteAllObjects); typedef boost::shared_ptr Shared; @@ -850,7 +886,7 @@ void MyFactorPosePoint2_constructor_70(int nargout, mxArray *out[], int nargin, *reinterpret_cast (mxGetData(out[0])) = self; } -void MyFactorPosePoint2_deconstructor_71(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void MyFactorPosePoint2_deconstructor_75(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr Shared; checkArguments("delete_MyFactorPosePoint2",nargout,nargin,1); @@ -863,18 +899,18 @@ void MyFactorPosePoint2_deconstructor_71(int nargout, mxArray *out[], int nargin } } -void aGlobalFunction_72(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void aGlobalFunction_76(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { checkArguments("aGlobalFunction",nargout,nargin,0); out[0] = wrap< Vector >(aGlobalFunction()); } -void overloadedGlobalFunction_73(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void overloadedGlobalFunction_77(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_74(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void overloadedGlobalFunction_78(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { checkArguments("overloadedGlobalFunction",nargout,nargin,2); int a = unwrap< int >(in[0]); @@ -1062,61 +1098,73 @@ void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) MyTemplatePoint2_templatedMethod_55(nargout, out, nargin-1, in+1); break; case 56: - MyTemplatePoint3_collectorInsertAndMakeBase_56(nargout, out, nargin-1, in+1); + MyTemplatePoint2_templatedMethod_56(nargout, out, nargin-1, in+1); break; case 57: - MyTemplatePoint3_upcastFromVoid_57(nargout, out, nargin-1, in+1); + MyTemplatePoint2_templatedMethod_57(nargout, out, nargin-1, in+1); break; case 58: - MyTemplatePoint3_constructor_58(nargout, out, nargin-1, in+1); + MyTemplatePoint3_collectorInsertAndMakeBase_58(nargout, out, nargin-1, in+1); break; case 59: - MyTemplatePoint3_deconstructor_59(nargout, out, nargin-1, in+1); + MyTemplatePoint3_upcastFromVoid_59(nargout, out, nargin-1, in+1); break; case 60: - MyTemplatePoint3_accept_T_60(nargout, out, nargin-1, in+1); + MyTemplatePoint3_constructor_60(nargout, out, nargin-1, in+1); break; case 61: - MyTemplatePoint3_accept_Tptr_61(nargout, out, nargin-1, in+1); + MyTemplatePoint3_deconstructor_61(nargout, out, nargin-1, in+1); break; case 62: - MyTemplatePoint3_create_MixedPtrs_62(nargout, out, nargin-1, in+1); + MyTemplatePoint3_accept_T_62(nargout, out, nargin-1, in+1); break; case 63: - MyTemplatePoint3_create_ptrs_63(nargout, out, nargin-1, in+1); + MyTemplatePoint3_accept_Tptr_63(nargout, out, nargin-1, in+1); break; case 64: - MyTemplatePoint3_return_T_64(nargout, out, nargin-1, in+1); + MyTemplatePoint3_create_MixedPtrs_64(nargout, out, nargin-1, in+1); break; case 65: - MyTemplatePoint3_return_Tptr_65(nargout, out, nargin-1, in+1); + MyTemplatePoint3_create_ptrs_65(nargout, out, nargin-1, in+1); break; case 66: - MyTemplatePoint3_return_ptrs_66(nargout, out, nargin-1, in+1); + MyTemplatePoint3_return_T_66(nargout, out, nargin-1, in+1); break; case 67: - MyTemplatePoint3_templatedMethod_67(nargout, out, nargin-1, in+1); + MyTemplatePoint3_return_Tptr_67(nargout, out, nargin-1, in+1); break; case 68: - MyTemplatePoint3_templatedMethod_68(nargout, out, nargin-1, in+1); + MyTemplatePoint3_return_ptrs_68(nargout, out, nargin-1, in+1); break; case 69: - MyFactorPosePoint2_collectorInsertAndMakeBase_69(nargout, out, nargin-1, in+1); + MyTemplatePoint3_templatedMethod_69(nargout, out, nargin-1, in+1); break; case 70: - MyFactorPosePoint2_constructor_70(nargout, out, nargin-1, in+1); + MyTemplatePoint3_templatedMethod_70(nargout, out, nargin-1, in+1); break; case 71: - MyFactorPosePoint2_deconstructor_71(nargout, out, nargin-1, in+1); + MyTemplatePoint3_templatedMethod_71(nargout, out, nargin-1, in+1); break; case 72: - aGlobalFunction_72(nargout, out, nargin-1, in+1); + MyTemplatePoint3_templatedMethod_72(nargout, out, nargin-1, in+1); break; case 73: - overloadedGlobalFunction_73(nargout, out, nargin-1, in+1); + MyFactorPosePoint2_collectorInsertAndMakeBase_73(nargout, out, nargin-1, in+1); break; case 74: - overloadedGlobalFunction_74(nargout, out, nargin-1, in+1); + MyFactorPosePoint2_constructor_74(nargout, out, nargin-1, in+1); + break; + case 75: + MyFactorPosePoint2_deconstructor_75(nargout, out, nargin-1, in+1); + break; + case 76: + aGlobalFunction_76(nargout, out, nargin-1, in+1); + break; + case 77: + overloadedGlobalFunction_77(nargout, out, nargin-1, in+1); + break; + case 78: + overloadedGlobalFunction_78(nargout, out, nargin-1, in+1); break; } } catch(const std::exception& e) { diff --git a/wrap/tests/expected2/overloadedGlobalFunction.m b/wrap/tests/expected2/overloadedGlobalFunction.m index 24758ed6e..fb912a880 100644 --- a/wrap/tests/expected2/overloadedGlobalFunction.m +++ b/wrap/tests/expected2/overloadedGlobalFunction.m @@ -1,8 +1,8 @@ function varargout = overloadedGlobalFunction(varargin) if length(varargin) == 1 && isa(varargin{1},'numeric') - varargout{1} = geometry_wrapper(73, varargin{:}); + varargout{1} = geometry_wrapper(77, varargin{:}); elseif length(varargin) == 2 && isa(varargin{1},'numeric') && isa(varargin{2},'double') - varargout{1} = geometry_wrapper(74, varargin{:}); + varargout{1} = geometry_wrapper(78, varargin{:}); else error('Arguments do not match any overload of function overloadedGlobalFunction'); end diff --git a/wrap/tests/geometry.h b/wrap/tests/geometry.h index 5a6cee1a5..f6465fa95 100644 --- a/wrap/tests/geometry.h +++ b/wrap/tests/geometry.h @@ -104,7 +104,7 @@ template virtual class MyTemplate : MyBase { MyTemplate(); - template + template void templatedMethod(const ARG& t); // Stress test templates and pointer combinations From 7fdcc98ea5bb3189e1641162713e25984901fa27 Mon Sep 17 00:00:00 2001 From: dellaert Date: Sat, 29 Nov 2014 13:50:04 +0100 Subject: [PATCH 013/126] Updated tests with serialization --- wrap/tests/expected/+gtsam/Point2.m | 90 ++ wrap/tests/expected/+gtsam/Point3.m | 93 +++ wrap/tests/expected/MyBase.m | 35 + wrap/tests/expected/MyFactorPosePoint2.m | 36 + wrap/tests/expected/MyTemplatePoint2.m | 156 ++++ wrap/tests/expected/MyTemplatePoint3.m | 156 ++++ wrap/tests/expected/Test.m | 16 +- wrap/tests/expected/aGlobalFunction.m | 2 +- wrap/tests/expected/geometry_wrapper.cpp | 766 +++++++++++++++--- .../tests/expected/overloadedGlobalFunction.m | 4 +- 10 files changed, 1229 insertions(+), 125 deletions(-) create mode 100644 wrap/tests/expected/+gtsam/Point2.m create mode 100644 wrap/tests/expected/+gtsam/Point3.m create mode 100644 wrap/tests/expected/MyBase.m create mode 100644 wrap/tests/expected/MyFactorPosePoint2.m create mode 100644 wrap/tests/expected/MyTemplatePoint2.m create mode 100644 wrap/tests/expected/MyTemplatePoint3.m diff --git a/wrap/tests/expected/+gtsam/Point2.m b/wrap/tests/expected/+gtsam/Point2.m new file mode 100644 index 000000000..308b35d9a --- /dev/null +++ b/wrap/tests/expected/+gtsam/Point2.m @@ -0,0 +1,90 @@ +%class Point2, see Doxygen page for details +%at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html +% +%-------Constructors------- +%Point2() +%Point2(double x, double y) +% +%-------Methods------- +%argChar(char a) : returns void +%argUChar(unsigned char a) : returns void +%dim() : returns int +%returnChar() : returns char +%vectorConfusion() : returns VectorNotEigen +%x() : returns double +%y() : returns double +% +classdef Point2 < handle + properties + ptr_gtsamPoint2 = 0 + end + methods + function obj = Point2(varargin) + if nargin == 2 && isa(varargin{1}, 'uint64') && varargin{1} == uint64(5139824614673773682) + my_ptr = varargin{2}; + geometry_wrapper(0, my_ptr); + elseif nargin == 0 + my_ptr = geometry_wrapper(1); + elseif nargin == 2 && isa(varargin{1},'double') && isa(varargin{2},'double') + my_ptr = geometry_wrapper(2, varargin{1}, varargin{2}); + else + error('Arguments do not match any overload of gtsam.Point2 constructor'); + end + obj.ptr_gtsamPoint2 = my_ptr; + end + + function delete(obj) + geometry_wrapper(3, obj.ptr_gtsamPoint2); + 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 = argChar(this, varargin) + % ARGCHAR usage: argChar(char a) : returns void + % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html + geometry_wrapper(4, this, varargin{:}); + end + + function varargout = argUChar(this, varargin) + % ARGUCHAR usage: argUChar(unsigned char a) : returns void + % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html + geometry_wrapper(5, this, varargin{:}); + end + + function varargout = dim(this, varargin) + % DIM usage: dim() : returns int + % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html + varargout{1} = geometry_wrapper(6, this, varargin{:}); + end + + function varargout = returnChar(this, varargin) + % RETURNCHAR usage: returnChar() : returns char + % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html + varargout{1} = geometry_wrapper(7, this, varargin{:}); + end + + function varargout = vectorConfusion(this, varargin) + % VECTORCONFUSION usage: vectorConfusion() : returns VectorNotEigen + % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html + varargout{1} = geometry_wrapper(8, this, varargin{:}); + end + + function varargout = x(this, varargin) + % X usage: x() : returns double + % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html + varargout{1} = geometry_wrapper(9, this, varargin{:}); + end + + function varargout = y(this, varargin) + % Y usage: y() : returns double + % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html + varargout{1} = geometry_wrapper(10, this, varargin{:}); + end + + end + + methods(Static = true) + end +end diff --git a/wrap/tests/expected/+gtsam/Point3.m b/wrap/tests/expected/+gtsam/Point3.m new file mode 100644 index 000000000..a9a28c14c --- /dev/null +++ b/wrap/tests/expected/+gtsam/Point3.m @@ -0,0 +1,93 @@ +%class Point3, see Doxygen page for details +%at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html +% +%-------Constructors------- +%Point3(double x, double y, double z) +% +%-------Methods------- +%norm() : returns double +% +%-------Static Methods------- +%StaticFunctionRet(double z) : returns gtsam::Point3 +%staticFunction() : returns double +% +%-------Serialization Interface------- +%string_serialize() : returns string +%string_deserialize(string serialized) : returns Point3 +% +classdef Point3 < handle + properties + ptr_gtsamPoint3 = 0 + end + methods + function obj = Point3(varargin) + if nargin == 2 && isa(varargin{1}, 'uint64') && varargin{1} == uint64(5139824614673773682) + my_ptr = varargin{2}; + geometry_wrapper(11, my_ptr); + elseif nargin == 3 && isa(varargin{1},'double') && isa(varargin{2},'double') && isa(varargin{3},'double') + my_ptr = geometry_wrapper(12, varargin{1}, varargin{2}, varargin{3}); + else + error('Arguments do not match any overload of gtsam.Point3 constructor'); + end + obj.ptr_gtsamPoint3 = my_ptr; + end + + function delete(obj) + geometry_wrapper(13, obj.ptr_gtsamPoint3); + 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 = norm(this, varargin) + % NORM usage: norm() : returns double + % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html + varargout{1} = geometry_wrapper(14, this, varargin{:}); + end + + function varargout = string_serialize(this, varargin) + % STRING_SERIALIZE usage: string_serialize() : returns string + % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html + if length(varargin) == 0 + varargout{1} = geometry_wrapper(15, this, varargin{:}); + else + error('Arguments do not match any overload of function gtsam.Point3.string_serialize'); + end + end + + function sobj = saveobj(obj) + % SAVEOBJ Saves the object to a matlab-readable format + sobj = obj.string_serialize(); + end + end + + methods(Static = true) + function varargout = StaticFunctionRet(varargin) + % STATICFUNCTIONRET usage: StaticFunctionRet(double z) : returns gtsam::Point3 + % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html + varargout{1} = geometry_wrapper(16, varargin{:}); + end + + function varargout = StaticFunction(varargin) + % STATICFUNCTION usage: staticFunction() : returns double + % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html + varargout{1} = geometry_wrapper(17, varargin{:}); + end + + function varargout = string_deserialize(varargin) + % STRING_DESERIALIZE usage: string_deserialize() : returns gtsam.Point3 + % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html + if length(varargin) == 1 + varargout{1} = geometry_wrapper(18, varargin{:}); + else + error('Arguments do not match any overload of function gtsam.Point3.string_deserialize'); + end + end + + function obj = loadobj(sobj) + % LOADOBJ Saves the object to a matlab-readable format + obj = gtsam.Point3.string_deserialize(sobj); + end + end +end diff --git a/wrap/tests/expected/MyBase.m b/wrap/tests/expected/MyBase.m new file mode 100644 index 000000000..34d3cb4c0 --- /dev/null +++ b/wrap/tests/expected/MyBase.m @@ -0,0 +1,35 @@ +%class MyBase, see Doxygen page for details +%at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html +% +classdef MyBase < handle + properties + ptr_MyBase = 0 + end + methods + function obj = MyBase(varargin) + if (nargin == 2 || (nargin == 3 && strcmp(varargin{3}, 'void'))) && isa(varargin{1}, 'uint64') && varargin{1} == uint64(5139824614673773682) + if nargin == 2 + my_ptr = varargin{2}; + else + my_ptr = geometry_wrapper(43, varargin{2}); + end + geometry_wrapper(42, my_ptr); + else + error('Arguments do not match any overload of MyBase constructor'); + end + obj.ptr_MyBase = my_ptr; + end + + function delete(obj) + geometry_wrapper(44, obj.ptr_MyBase); + 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/wrap/tests/expected/MyFactorPosePoint2.m b/wrap/tests/expected/MyFactorPosePoint2.m new file mode 100644 index 000000000..496a2c1e8 --- /dev/null +++ b/wrap/tests/expected/MyFactorPosePoint2.m @@ -0,0 +1,36 @@ +%class MyFactorPosePoint2, see Doxygen page for details +%at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html +% +%-------Constructors------- +%MyFactorPosePoint2(size_t key1, size_t key2, double measured, Base noiseModel) +% +classdef MyFactorPosePoint2 < handle + properties + ptr_MyFactorPosePoint2 = 0 + end + methods + function obj = MyFactorPosePoint2(varargin) + if nargin == 2 && isa(varargin{1}, 'uint64') && varargin{1} == uint64(5139824614673773682) + my_ptr = varargin{2}; + geometry_wrapper(75, 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(76, varargin{1}, varargin{2}, varargin{3}, varargin{4}); + else + error('Arguments do not match any overload of MyFactorPosePoint2 constructor'); + end + obj.ptr_MyFactorPosePoint2 = my_ptr; + end + + function delete(obj) + geometry_wrapper(77, obj.ptr_MyFactorPosePoint2); + 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/wrap/tests/expected/MyTemplatePoint2.m b/wrap/tests/expected/MyTemplatePoint2.m new file mode 100644 index 000000000..e6adb3d2c --- /dev/null +++ b/wrap/tests/expected/MyTemplatePoint2.m @@ -0,0 +1,156 @@ +%class MyTemplatePoint2, see Doxygen page for details +%at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html +% +%-------Constructors------- +%MyTemplatePoint2() +% +%-------Methods------- +%accept_T(Point2 value) : returns void +%accept_Tptr(Point2 value) : returns void +%create_MixedPtrs() : returns pair< gtsam::Point2, gtsam::Point2 > +%create_ptrs() : returns pair< gtsam::Point2, gtsam::Point2 > +%return_T(Point2 value) : returns gtsam::Point2 +%return_Tptr(Point2 value) : returns gtsam::Point2 +%return_ptrs(Point2 p1, Point2 p2) : returns pair< gtsam::Point2, gtsam::Point2 > +%templatedMethodMatrix(Matrix t) : returns void +%templatedMethodPoint2(Point2 t) : returns void +%templatedMethodPoint3(Point3 t) : returns void +%templatedMethodVector(Vector t) : returns void +% +classdef MyTemplatePoint2 < MyBase + properties + ptr_MyTemplatePoint2 = 0 + end + methods + function obj = MyTemplatePoint2(varargin) + if (nargin == 2 || (nargin == 3 && strcmp(varargin{3}, 'void'))) && isa(varargin{1}, 'uint64') && varargin{1} == uint64(5139824614673773682) + if nargin == 2 + my_ptr = varargin{2}; + else + my_ptr = geometry_wrapper(46, varargin{2}); + end + base_ptr = geometry_wrapper(45, my_ptr); + elseif nargin == 0 + [ my_ptr, base_ptr ] = geometry_wrapper(47); + else + error('Arguments do not match any overload of MyTemplatePoint2 constructor'); + end + obj = obj@MyBase(uint64(5139824614673773682), base_ptr); + obj.ptr_MyTemplatePoint2 = my_ptr; + end + + function delete(obj) + geometry_wrapper(48, obj.ptr_MyTemplatePoint2); + 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 = accept_T(this, varargin) + % ACCEPT_T usage: accept_T(Point2 value) : returns void + % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html + if length(varargin) == 1 && isa(varargin{1},'gtsam.Point2') + geometry_wrapper(49, this, varargin{:}); + else + error('Arguments do not match any overload of function MyTemplatePoint2.accept_T'); + end + end + + function varargout = accept_Tptr(this, varargin) + % ACCEPT_TPTR usage: accept_Tptr(Point2 value) : returns void + % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html + if length(varargin) == 1 && isa(varargin{1},'gtsam.Point2') + geometry_wrapper(50, this, varargin{:}); + else + error('Arguments do not match any overload of function MyTemplatePoint2.accept_Tptr'); + end + end + + function varargout = create_MixedPtrs(this, varargin) + % CREATE_MIXEDPTRS usage: create_MixedPtrs() : returns pair< gtsam::Point2, gtsam::Point2 > + % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html + [ varargout{1} varargout{2} ] = geometry_wrapper(51, this, varargin{:}); + end + + function varargout = create_ptrs(this, varargin) + % CREATE_PTRS usage: create_ptrs() : returns pair< gtsam::Point2, gtsam::Point2 > + % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html + [ varargout{1} varargout{2} ] = geometry_wrapper(52, this, varargin{:}); + end + + function varargout = return_T(this, varargin) + % RETURN_T usage: return_T(Point2 value) : returns gtsam::Point2 + % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html + if length(varargin) == 1 && isa(varargin{1},'gtsam.Point2') + varargout{1} = geometry_wrapper(53, this, varargin{:}); + else + error('Arguments do not match any overload of function MyTemplatePoint2.return_T'); + end + end + + function varargout = return_Tptr(this, varargin) + % RETURN_TPTR usage: return_Tptr(Point2 value) : returns gtsam::Point2 + % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html + if length(varargin) == 1 && isa(varargin{1},'gtsam.Point2') + varargout{1} = geometry_wrapper(54, this, varargin{:}); + else + error('Arguments do not match any overload of function MyTemplatePoint2.return_Tptr'); + end + end + + function varargout = return_ptrs(this, varargin) + % RETURN_PTRS usage: return_ptrs(Point2 p1, Point2 p2) : returns pair< gtsam::Point2, gtsam::Point2 > + % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html + if length(varargin) == 2 && isa(varargin{1},'gtsam.Point2') && isa(varargin{2},'gtsam.Point2') + [ varargout{1} varargout{2} ] = geometry_wrapper(55, this, varargin{:}); + else + error('Arguments do not match any overload of function MyTemplatePoint2.return_ptrs'); + end + end + + function varargout = templatedMethodMatrix(this, varargin) + % TEMPLATEDMETHODMATRIX usage: templatedMethodMatrix(Matrix t) : returns void + % 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') + geometry_wrapper(56, this, varargin{:}); + else + error('Arguments do not match any overload of function MyTemplatePoint2.templatedMethod'); + end + end + + function varargout = templatedMethodPoint2(this, varargin) + % TEMPLATEDMETHODPOINT2 usage: templatedMethodPoint2(Point2 t) : returns void + % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html + if length(varargin) == 1 && isa(varargin{1},'gtsam.Point2') + geometry_wrapper(57, this, varargin{:}); + else + error('Arguments do not match any overload of function MyTemplatePoint2.templatedMethod'); + end + end + + function varargout = templatedMethodPoint3(this, varargin) + % TEMPLATEDMETHODPOINT3 usage: templatedMethodPoint3(Point3 t) : returns void + % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html + if length(varargin) == 1 && isa(varargin{1},'gtsam.Point3') + geometry_wrapper(58, this, varargin{:}); + else + error('Arguments do not match any overload of function MyTemplatePoint2.templatedMethod'); + end + end + + function varargout = templatedMethodVector(this, varargin) + % TEMPLATEDMETHODVECTOR usage: templatedMethodVector(Vector t) : returns void + % 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') + geometry_wrapper(59, this, varargin{:}); + else + error('Arguments do not match any overload of function MyTemplatePoint2.templatedMethod'); + end + end + + end + + methods(Static = true) + end +end diff --git a/wrap/tests/expected/MyTemplatePoint3.m b/wrap/tests/expected/MyTemplatePoint3.m new file mode 100644 index 000000000..9819b5ee1 --- /dev/null +++ b/wrap/tests/expected/MyTemplatePoint3.m @@ -0,0 +1,156 @@ +%class MyTemplatePoint3, see Doxygen page for details +%at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html +% +%-------Constructors------- +%MyTemplatePoint3() +% +%-------Methods------- +%accept_T(Point3 value) : returns void +%accept_Tptr(Point3 value) : returns void +%create_MixedPtrs() : returns pair< gtsam::Point3, gtsam::Point3 > +%create_ptrs() : returns pair< gtsam::Point3, gtsam::Point3 > +%return_T(Point3 value) : returns gtsam::Point3 +%return_Tptr(Point3 value) : returns gtsam::Point3 +%return_ptrs(Point3 p1, Point3 p2) : returns pair< gtsam::Point3, gtsam::Point3 > +%templatedMethodMatrix(Matrix t) : returns void +%templatedMethodPoint2(Point2 t) : returns void +%templatedMethodPoint3(Point3 t) : returns void +%templatedMethodVector(Vector t) : returns void +% +classdef MyTemplatePoint3 < MyBase + properties + ptr_MyTemplatePoint3 = 0 + end + methods + function obj = MyTemplatePoint3(varargin) + if (nargin == 2 || (nargin == 3 && strcmp(varargin{3}, 'void'))) && isa(varargin{1}, 'uint64') && varargin{1} == uint64(5139824614673773682) + if nargin == 2 + my_ptr = varargin{2}; + else + my_ptr = geometry_wrapper(61, varargin{2}); + end + base_ptr = geometry_wrapper(60, my_ptr); + elseif nargin == 0 + [ my_ptr, base_ptr ] = geometry_wrapper(62); + else + error('Arguments do not match any overload of MyTemplatePoint3 constructor'); + end + obj = obj@MyBase(uint64(5139824614673773682), base_ptr); + obj.ptr_MyTemplatePoint3 = my_ptr; + end + + function delete(obj) + geometry_wrapper(63, obj.ptr_MyTemplatePoint3); + 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 = accept_T(this, varargin) + % ACCEPT_T usage: accept_T(Point3 value) : returns void + % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html + if length(varargin) == 1 && isa(varargin{1},'gtsam.Point3') + geometry_wrapper(64, this, varargin{:}); + else + error('Arguments do not match any overload of function MyTemplatePoint3.accept_T'); + end + end + + function varargout = accept_Tptr(this, varargin) + % ACCEPT_TPTR usage: accept_Tptr(Point3 value) : returns void + % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html + if length(varargin) == 1 && isa(varargin{1},'gtsam.Point3') + geometry_wrapper(65, this, varargin{:}); + else + error('Arguments do not match any overload of function MyTemplatePoint3.accept_Tptr'); + end + end + + function varargout = create_MixedPtrs(this, varargin) + % CREATE_MIXEDPTRS usage: create_MixedPtrs() : returns pair< gtsam::Point3, gtsam::Point3 > + % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html + [ varargout{1} varargout{2} ] = geometry_wrapper(66, this, varargin{:}); + end + + function varargout = create_ptrs(this, varargin) + % CREATE_PTRS usage: create_ptrs() : returns pair< gtsam::Point3, gtsam::Point3 > + % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html + [ varargout{1} varargout{2} ] = geometry_wrapper(67, this, varargin{:}); + end + + function varargout = return_T(this, varargin) + % RETURN_T usage: return_T(Point3 value) : returns gtsam::Point3 + % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html + if length(varargin) == 1 && isa(varargin{1},'gtsam.Point3') + varargout{1} = geometry_wrapper(68, this, varargin{:}); + else + error('Arguments do not match any overload of function MyTemplatePoint3.return_T'); + end + end + + function varargout = return_Tptr(this, varargin) + % RETURN_TPTR usage: return_Tptr(Point3 value) : returns gtsam::Point3 + % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html + if length(varargin) == 1 && isa(varargin{1},'gtsam.Point3') + varargout{1} = geometry_wrapper(69, this, varargin{:}); + else + error('Arguments do not match any overload of function MyTemplatePoint3.return_Tptr'); + end + end + + function varargout = return_ptrs(this, varargin) + % RETURN_PTRS usage: return_ptrs(Point3 p1, Point3 p2) : returns pair< gtsam::Point3, gtsam::Point3 > + % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html + if length(varargin) == 2 && isa(varargin{1},'gtsam.Point3') && isa(varargin{2},'gtsam.Point3') + [ varargout{1} varargout{2} ] = geometry_wrapper(70, this, varargin{:}); + else + error('Arguments do not match any overload of function MyTemplatePoint3.return_ptrs'); + end + end + + function varargout = templatedMethodMatrix(this, varargin) + % TEMPLATEDMETHODMATRIX usage: templatedMethodMatrix(Matrix t) : returns void + % 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') + geometry_wrapper(71, this, varargin{:}); + else + error('Arguments do not match any overload of function MyTemplatePoint3.templatedMethod'); + end + end + + function varargout = templatedMethodPoint2(this, varargin) + % TEMPLATEDMETHODPOINT2 usage: templatedMethodPoint2(Point2 t) : returns void + % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html + if length(varargin) == 1 && isa(varargin{1},'gtsam.Point2') + geometry_wrapper(72, this, varargin{:}); + else + error('Arguments do not match any overload of function MyTemplatePoint3.templatedMethod'); + end + end + + function varargout = templatedMethodPoint3(this, varargin) + % TEMPLATEDMETHODPOINT3 usage: templatedMethodPoint3(Point3 t) : returns void + % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html + if length(varargin) == 1 && isa(varargin{1},'gtsam.Point3') + geometry_wrapper(73, this, varargin{:}); + else + error('Arguments do not match any overload of function MyTemplatePoint3.templatedMethod'); + end + end + + function varargout = templatedMethodVector(this, varargin) + % TEMPLATEDMETHODVECTOR usage: templatedMethodVector(Vector t) : returns void + % 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') + geometry_wrapper(74, this, varargin{:}); + else + error('Arguments do not match any overload of function MyTemplatePoint3.templatedMethod'); + end + end + + end + + methods(Static = true) + end +end diff --git a/wrap/tests/expected/Test.m b/wrap/tests/expected/Test.m index 1afd15efe..352312789 100644 --- a/wrap/tests/expected/Test.m +++ b/wrap/tests/expected/Test.m @@ -7,10 +7,10 @@ % %-------Methods------- %arg_EigenConstRef(Matrix value) : returns void -%create_MixedPtrs() : returns pair< Test, SharedTest > -%create_ptrs() : returns pair< SharedTest, SharedTest > +%create_MixedPtrs() : returns pair< Test, Test > +%create_ptrs() : returns pair< Test, Test > %print() : returns void -%return_Point2Ptr(bool value) : returns Point2 +%return_Point2Ptr(bool value) : returns gtsam::Point2 %return_Test(Test value) : returns Test %return_TestPtr(Test value) : returns Test %return_bool(bool value) : returns bool @@ -20,7 +20,7 @@ %return_matrix1(Matrix value) : returns Matrix %return_matrix2(Matrix value) : returns Matrix %return_pair(Vector v, Matrix A) : returns pair< Vector, Matrix > -%return_ptrs(Test p1, Test p2) : returns pair< SharedTest, SharedTest > +%return_ptrs(Test p1, Test p2) : returns pair< Test, Test > %return_size_t(size_t value) : returns size_t %return_string(string value) : returns string %return_vector1(Vector value) : returns Vector @@ -64,13 +64,13 @@ classdef Test < handle end function varargout = create_MixedPtrs(this, varargin) - % CREATE_MIXEDPTRS usage: create_MixedPtrs() : returns pair< Test, SharedTest > + % CREATE_MIXEDPTRS usage: create_MixedPtrs() : returns pair< Test, Test > % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html [ varargout{1} varargout{2} ] = geometry_wrapper(24, this, varargin{:}); end function varargout = create_ptrs(this, varargin) - % CREATE_PTRS usage: create_ptrs() : returns pair< SharedTest, SharedTest > + % CREATE_PTRS usage: create_ptrs() : returns pair< Test, Test > % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html [ varargout{1} varargout{2} ] = geometry_wrapper(25, this, varargin{:}); end @@ -82,7 +82,7 @@ classdef Test < handle end function varargout = return_Point2Ptr(this, varargin) - % RETURN_POINT2PTR usage: return_Point2Ptr(bool value) : returns Point2 + % RETURN_POINT2PTR usage: return_Point2Ptr(bool value) : returns gtsam::Point2 % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html varargout{1} = geometry_wrapper(27, this, varargin{:}); end @@ -166,7 +166,7 @@ classdef Test < handle end function varargout = return_ptrs(this, varargin) - % RETURN_PTRS usage: return_ptrs(Test p1, Test p2) : returns pair< SharedTest, SharedTest > + % RETURN_PTRS usage: return_ptrs(Test p1, Test p2) : returns pair< Test, Test > % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html if length(varargin) == 2 && isa(varargin{1},'Test') && isa(varargin{2},'Test') [ varargout{1} varargout{2} ] = geometry_wrapper(37, this, varargin{:}); diff --git a/wrap/tests/expected/aGlobalFunction.m b/wrap/tests/expected/aGlobalFunction.m index 94e9b4a67..2e725c658 100644 --- a/wrap/tests/expected/aGlobalFunction.m +++ b/wrap/tests/expected/aGlobalFunction.m @@ -1,6 +1,6 @@ function varargout = aGlobalFunction(varargin) if length(varargin) == 0 - varargout{1} = geometry_wrapper(42, varargin{:}); + varargout{1} = geometry_wrapper(78, varargin{:}); else error('Arguments do not match any overload of function aGlobalFunction'); end diff --git a/wrap/tests/expected/geometry_wrapper.cpp b/wrap/tests/expected/geometry_wrapper.cpp index b34112718..158e326bc 100644 --- a/wrap/tests/expected/geometry_wrapper.cpp +++ b/wrap/tests/expected/geometry_wrapper.cpp @@ -8,16 +8,27 @@ #include +typedef MyTemplate MyTemplatePoint2; +typedef MyTemplate MyTemplatePoint3; +typedef MyFactor MyFactorPosePoint2; -BOOST_CLASS_EXPORT_GUID(Point2, "Point2"); -BOOST_CLASS_EXPORT_GUID(Point3, "Point3"); +BOOST_CLASS_EXPORT_GUID(gtsam::Point2, "gtsamPoint2"); +BOOST_CLASS_EXPORT_GUID(gtsam::Point3, "gtsamPoint3"); -typedef std::set*> Collector_Point2; -static Collector_Point2 collector_Point2; -typedef std::set*> Collector_Point3; -static Collector_Point3 collector_Point3; +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_MyTemplatePoint3; +static Collector_MyTemplatePoint3 collector_MyTemplatePoint3; +typedef std::set*> Collector_MyFactorPosePoint2; +static Collector_MyFactorPosePoint2 collector_MyFactorPosePoint2; void _deleteAllObjects() { @@ -25,16 +36,16 @@ void _deleteAllObjects() std::streambuf *outbuf = std::cout.rdbuf(&mout); bool anyDeleted = false; - { for(Collector_Point2::iterator iter = collector_Point2.begin(); - iter != collector_Point2.end(); ) { + { for(Collector_gtsamPoint2::iterator iter = collector_gtsamPoint2.begin(); + iter != collector_gtsamPoint2.end(); ) { delete *iter; - collector_Point2.erase(iter++); + collector_gtsamPoint2.erase(iter++); anyDeleted = true; } } - { for(Collector_Point3::iterator iter = collector_Point3.begin(); - iter != collector_Point3.end(); ) { + { for(Collector_gtsamPoint3::iterator iter = collector_gtsamPoint3.begin(); + iter != collector_gtsamPoint3.end(); ) { delete *iter; - collector_Point3.erase(iter++); + collector_gtsamPoint3.erase(iter++); anyDeleted = true; } } { for(Collector_Test::iterator iter = collector_Test.begin(); @@ -43,6 +54,30 @@ void _deleteAllObjects() 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_MyTemplatePoint3::iterator iter = collector_MyTemplatePoint3.begin(); + iter != collector_MyTemplatePoint3.end(); ) { + delete *iter; + collector_MyTemplatePoint3.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" @@ -55,6 +90,9 @@ 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(MyTemplatePoint3).name(), "MyTemplatePoint3")); mxArray *registry = mexGetVariable("global", "gtsamwrap_rttiRegistry"); if(!registry) @@ -78,191 +116,191 @@ void _geometry_RTTIRegister() { } } -void Point2_collectorInsertAndMakeBase_0(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void gtsamPoint2_collectorInsertAndMakeBase_0(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { mexAtExit(&_deleteAllObjects); - typedef boost::shared_ptr Shared; + typedef boost::shared_ptr Shared; Shared *self = *reinterpret_cast (mxGetData(in[0])); - collector_Point2.insert(self); + collector_gtsamPoint2.insert(self); } -void Point2_constructor_1(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void gtsamPoint2_constructor_1(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { mexAtExit(&_deleteAllObjects); - typedef boost::shared_ptr Shared; + typedef boost::shared_ptr Shared; - Shared *self = new Shared(new Point2()); - collector_Point2.insert(self); + 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 Point2_constructor_2(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void gtsamPoint2_constructor_2(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { mexAtExit(&_deleteAllObjects); - typedef boost::shared_ptr Shared; + typedef boost::shared_ptr Shared; double x = unwrap< double >(in[0]); double y = unwrap< double >(in[1]); - Shared *self = new Shared(new Point2(x,y)); - collector_Point2.insert(self); + 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 Point2_deconstructor_3(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void gtsamPoint2_deconstructor_3(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { - typedef boost::shared_ptr Shared; - checkArguments("delete_Point2",nargout,nargin,1); + typedef boost::shared_ptr Shared; + checkArguments("delete_gtsamPoint2",nargout,nargin,1); Shared *self = *reinterpret_cast(mxGetData(in[0])); - Collector_Point2::iterator item; - item = collector_Point2.find(self); - if(item != collector_Point2.end()) { + Collector_gtsamPoint2::iterator item; + item = collector_gtsamPoint2.find(self); + if(item != collector_gtsamPoint2.end()) { delete self; - collector_Point2.erase(item); + collector_gtsamPoint2.erase(item); } } -void Point2_argChar_4(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void gtsamPoint2_argChar_4(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { - typedef boost::shared_ptr Shared; + typedef boost::shared_ptr Shared; checkArguments("argChar",nargout,nargin-1,1); - Shared obj = unwrap_shared_ptr(in[0], "ptr_Point2"); + Shared obj = unwrap_shared_ptr(in[0], "ptr_gtsamPoint2"); char a = unwrap< char >(in[1]); obj->argChar(a); } -void Point2_argUChar_5(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void gtsamPoint2_argUChar_5(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { - typedef boost::shared_ptr Shared; + typedef boost::shared_ptr Shared; checkArguments("argUChar",nargout,nargin-1,1); - Shared obj = unwrap_shared_ptr(in[0], "ptr_Point2"); + Shared obj = unwrap_shared_ptr(in[0], "ptr_gtsamPoint2"); unsigned char a = unwrap< unsigned char >(in[1]); obj->argUChar(a); } -void Point2_dim_6(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void gtsamPoint2_dim_6(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { - typedef boost::shared_ptr Shared; + typedef boost::shared_ptr Shared; checkArguments("dim",nargout,nargin-1,0); - Shared obj = unwrap_shared_ptr(in[0], "ptr_Point2"); + Shared obj = unwrap_shared_ptr(in[0], "ptr_gtsamPoint2"); out[0] = wrap< int >(obj->dim()); } -void Point2_returnChar_7(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void gtsamPoint2_returnChar_7(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { - typedef boost::shared_ptr Shared; + typedef boost::shared_ptr Shared; checkArguments("returnChar",nargout,nargin-1,0); - Shared obj = unwrap_shared_ptr(in[0], "ptr_Point2"); + Shared obj = unwrap_shared_ptr(in[0], "ptr_gtsamPoint2"); out[0] = wrap< char >(obj->returnChar()); } -void Point2_vectorConfusion_8(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void gtsamPoint2_vectorConfusion_8(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr SharedVectorNotEigen; - typedef boost::shared_ptr Shared; + typedef boost::shared_ptr Shared; checkArguments("vectorConfusion",nargout,nargin-1,0); - Shared obj = unwrap_shared_ptr(in[0], "ptr_Point2"); + Shared obj = unwrap_shared_ptr(in[0], "ptr_gtsamPoint2"); out[0] = wrap_shared_ptr(SharedVectorNotEigen(new VectorNotEigen(obj->vectorConfusion())),"VectorNotEigen", false); } -void Point2_x_9(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void gtsamPoint2_x_9(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { - typedef boost::shared_ptr Shared; + typedef boost::shared_ptr Shared; checkArguments("x",nargout,nargin-1,0); - Shared obj = unwrap_shared_ptr(in[0], "ptr_Point2"); + Shared obj = unwrap_shared_ptr(in[0], "ptr_gtsamPoint2"); out[0] = wrap< double >(obj->x()); } -void Point2_y_10(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void gtsamPoint2_y_10(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { - typedef boost::shared_ptr Shared; + typedef boost::shared_ptr Shared; checkArguments("y",nargout,nargin-1,0); - Shared obj = unwrap_shared_ptr(in[0], "ptr_Point2"); + Shared obj = unwrap_shared_ptr(in[0], "ptr_gtsamPoint2"); out[0] = wrap< double >(obj->y()); } -void Point3_collectorInsertAndMakeBase_11(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void gtsamPoint3_collectorInsertAndMakeBase_11(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { mexAtExit(&_deleteAllObjects); - typedef boost::shared_ptr Shared; + typedef boost::shared_ptr Shared; Shared *self = *reinterpret_cast (mxGetData(in[0])); - collector_Point3.insert(self); + collector_gtsamPoint3.insert(self); } -void Point3_constructor_12(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void gtsamPoint3_constructor_12(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { mexAtExit(&_deleteAllObjects); - typedef boost::shared_ptr Shared; + 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 Point3(x,y,z)); - collector_Point3.insert(self); + 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 Point3_deconstructor_13(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void gtsamPoint3_deconstructor_13(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { - typedef boost::shared_ptr Shared; - checkArguments("delete_Point3",nargout,nargin,1); + typedef boost::shared_ptr Shared; + checkArguments("delete_gtsamPoint3",nargout,nargin,1); Shared *self = *reinterpret_cast(mxGetData(in[0])); - Collector_Point3::iterator item; - item = collector_Point3.find(self); - if(item != collector_Point3.end()) { + Collector_gtsamPoint3::iterator item; + item = collector_gtsamPoint3.find(self); + if(item != collector_gtsamPoint3.end()) { delete self; - collector_Point3.erase(item); + collector_gtsamPoint3.erase(item); } } -void Point3_norm_14(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void gtsamPoint3_norm_14(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { - typedef boost::shared_ptr Shared; + typedef boost::shared_ptr Shared; checkArguments("norm",nargout,nargin-1,0); - Shared obj = unwrap_shared_ptr(in[0], "ptr_Point3"); + Shared obj = unwrap_shared_ptr(in[0], "ptr_gtsamPoint3"); out[0] = wrap< double >(obj->norm()); } -void Point3_string_serialize_15(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void gtsamPoint3_string_serialize_15(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { - typedef boost::shared_ptr Shared; + typedef boost::shared_ptr Shared; checkArguments("string_serialize",nargout,nargin-1,0); - Shared obj = unwrap_shared_ptr(in[0], "ptr_Point3"); - std::ostringstream out_archive_stream; + 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 Point3_StaticFunctionRet_16(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void gtsamPoint3_StaticFunctionRet_16(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { - typedef boost::shared_ptr SharedPoint3; - typedef boost::shared_ptr Shared; - checkArguments("Point3.StaticFunctionRet",nargout,nargin,1); + typedef boost::shared_ptr SharedPoint3; + typedef boost::shared_ptr Shared; + checkArguments("gtsamPoint3.StaticFunctionRet",nargout,nargin,1); double z = unwrap< double >(in[0]); - out[0] = wrap_shared_ptr(SharedPoint3(new Point3(Point3::StaticFunctionRet(z))),"Point3", false); + out[0] = wrap_shared_ptr(SharedPoint3(new gtsam::Point3(gtsam::Point3::StaticFunctionRet(z))),"gtsam.Point3", false); } -void Point3_staticFunction_17(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void gtsamPoint3_staticFunction_17(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { - typedef boost::shared_ptr Shared; - checkArguments("Point3.staticFunction",nargout,nargin,0); - out[0] = wrap< double >(Point3::staticFunction()); + typedef boost::shared_ptr Shared; + checkArguments("gtsamPoint3.staticFunction",nargout,nargin,0); + out[0] = wrap< double >(gtsam::Point3::staticFunction()); } -void Point3_string_deserialize_18(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void gtsamPoint3_string_deserialize_18(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { - typedef boost::shared_ptr Shared; - checkArguments("Point3.string_deserialize",nargout,nargin,1); + typedef boost::shared_ptr Shared; + checkArguments("gtsamPoint3.string_deserialize",nargout,nargin,1); string serialized = unwrap< string >(in[0]); - std::istringstream in_archive_stream(serialized); + istringstream in_archive_stream(serialized); boost::archive::text_iarchive in_archive(in_archive_stream); - Shared output(new Point3()); + Shared output(new gtsam::Point3()); in_archive >> *output; - out[0] = wrap_shared_ptr(output,"Point3", false); + out[0] = wrap_shared_ptr(output,"gtsam.Point3", false); } void Test_collectorInsertAndMakeBase_19(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { @@ -353,12 +391,12 @@ void Test_print_26(int nargout, mxArray *out[], int nargin, const mxArray *in[]) void Test_return_Point2Ptr_27(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { - typedef boost::shared_ptr SharedPoint2; + typedef boost::shared_ptr SharedPoint2; typedef boost::shared_ptr Shared; checkArguments("return_Point2Ptr",nargout,nargin-1,1); Shared obj = unwrap_shared_ptr(in[0], "ptr_Test"); bool value = unwrap< bool >(in[1]); - out[0] = wrap_shared_ptr(obj->return_Point2Ptr(value),"Point2", false); + out[0] = wrap_shared_ptr(obj->return_Point2Ptr(value),"gtsam.Point2", false); } void Test_return_Test_28(int nargout, mxArray *out[], int nargin, const mxArray *in[]) @@ -497,18 +535,410 @@ void Test_return_vector2_41(int nargout, mxArray *out[], int nargin, const mxArr out[0] = wrap< Vector >(obj->return_vector2(value)); } -void aGlobalFunction_42(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void MyBase_collectorInsertAndMakeBase_42(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_43(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_44(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_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_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_46(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_47(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + mexAtExit(&_deleteAllObjects); + typedef boost::shared_ptr Shared; + + Shared *self = new Shared(new MyTemplatePoint2()); + 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_48(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_49(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + typedef boost::shared_ptr Shared; + checkArguments("accept_T",nargout,nargin-1,1); + Shared obj = unwrap_shared_ptr(in[0], "ptr_MyTemplatePoint2"); + gtsam::Point2& value = *unwrap_shared_ptr< gtsam::Point2 >(in[1], "ptr_gtsamPoint2"); + obj->accept_T(value); +} + +void MyTemplatePoint2_accept_Tptr_50(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + typedef boost::shared_ptr Shared; + checkArguments("accept_Tptr",nargout,nargin-1,1); + Shared obj = unwrap_shared_ptr(in[0], "ptr_MyTemplatePoint2"); + boost::shared_ptr value = unwrap_shared_ptr< gtsam::Point2 >(in[1], "ptr_gtsamPoint2"); + obj->accept_Tptr(value); +} + +void MyTemplatePoint2_create_MixedPtrs_51(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + typedef boost::shared_ptr SharedPoint2; + typedef boost::shared_ptr SharedPoint2; + typedef boost::shared_ptr Shared; + checkArguments("create_MixedPtrs",nargout,nargin-1,0); + Shared obj = unwrap_shared_ptr(in[0], "ptr_MyTemplatePoint2"); + pair< gtsam::Point2, SharedPoint2 > pairResult = obj->create_MixedPtrs(); + out[0] = wrap_shared_ptr(SharedPoint2(new gtsam::Point2(pairResult.first)),"gtsam.Point2", false); + out[1] = wrap_shared_ptr(pairResult.second,"gtsam.Point2", false); +} + +void MyTemplatePoint2_create_ptrs_52(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + typedef boost::shared_ptr SharedPoint2; + typedef boost::shared_ptr SharedPoint2; + typedef boost::shared_ptr Shared; + checkArguments("create_ptrs",nargout,nargin-1,0); + Shared obj = unwrap_shared_ptr(in[0], "ptr_MyTemplatePoint2"); + pair< SharedPoint2, SharedPoint2 > pairResult = obj->create_ptrs(); + out[0] = wrap_shared_ptr(pairResult.first,"gtsam.Point2", false); + out[1] = wrap_shared_ptr(pairResult.second,"gtsam.Point2", false); +} + +void MyTemplatePoint2_return_T_53(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + typedef boost::shared_ptr SharedPoint2; + typedef boost::shared_ptr Shared; + checkArguments("return_T",nargout,nargin-1,1); + Shared obj = unwrap_shared_ptr(in[0], "ptr_MyTemplatePoint2"); + boost::shared_ptr value = unwrap_shared_ptr< gtsam::Point2 >(in[1], "ptr_gtsamPoint2"); + out[0] = wrap_shared_ptr(SharedPoint2(new gtsam::Point2(obj->return_T(value))),"gtsam.Point2", false); +} + +void MyTemplatePoint2_return_Tptr_54(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + typedef boost::shared_ptr SharedPoint2; + typedef boost::shared_ptr Shared; + checkArguments("return_Tptr",nargout,nargin-1,1); + Shared obj = unwrap_shared_ptr(in[0], "ptr_MyTemplatePoint2"); + boost::shared_ptr value = unwrap_shared_ptr< gtsam::Point2 >(in[1], "ptr_gtsamPoint2"); + out[0] = wrap_shared_ptr(obj->return_Tptr(value),"gtsam.Point2", false); +} + +void MyTemplatePoint2_return_ptrs_55(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + typedef boost::shared_ptr SharedPoint2; + typedef boost::shared_ptr SharedPoint2; + typedef boost::shared_ptr Shared; + checkArguments("return_ptrs",nargout,nargin-1,2); + Shared obj = unwrap_shared_ptr(in[0], "ptr_MyTemplatePoint2"); + boost::shared_ptr p1 = unwrap_shared_ptr< gtsam::Point2 >(in[1], "ptr_gtsamPoint2"); + boost::shared_ptr p2 = unwrap_shared_ptr< gtsam::Point2 >(in[2], "ptr_gtsamPoint2"); + pair< SharedPoint2, SharedPoint2 > pairResult = obj->return_ptrs(p1,p2); + out[0] = wrap_shared_ptr(pairResult.first,"gtsam.Point2", false); + out[1] = wrap_shared_ptr(pairResult.second,"gtsam.Point2", false); +} + +void MyTemplatePoint2_templatedMethod_56(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + typedef boost::shared_ptr Shared; + checkArguments("templatedMethodMatrix",nargout,nargin-1,1); + Shared obj = unwrap_shared_ptr(in[0], "ptr_MyTemplatePoint2"); + Matrix& t = *unwrap_shared_ptr< Matrix >(in[1], "ptr_Matrix"); + obj->templatedMethod(t); +} + +void MyTemplatePoint2_templatedMethod_57(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + typedef boost::shared_ptr Shared; + checkArguments("templatedMethodPoint2",nargout,nargin-1,1); + Shared obj = unwrap_shared_ptr(in[0], "ptr_MyTemplatePoint2"); + gtsam::Point2& t = *unwrap_shared_ptr< gtsam::Point2 >(in[1], "ptr_gtsamPoint2"); + obj->templatedMethod(t); +} + +void MyTemplatePoint2_templatedMethod_58(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + typedef boost::shared_ptr Shared; + checkArguments("templatedMethodPoint3",nargout,nargin-1,1); + Shared obj = unwrap_shared_ptr(in[0], "ptr_MyTemplatePoint2"); + gtsam::Point3& t = *unwrap_shared_ptr< gtsam::Point3 >(in[1], "ptr_gtsamPoint3"); + obj->templatedMethod(t); +} + +void MyTemplatePoint2_templatedMethod_59(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + typedef boost::shared_ptr Shared; + checkArguments("templatedMethodVector",nargout,nargin-1,1); + Shared obj = unwrap_shared_ptr(in[0], "ptr_MyTemplatePoint2"); + Vector& t = *unwrap_shared_ptr< Vector >(in[1], "ptr_Vector"); + obj->templatedMethod(t); +} + +void MyTemplatePoint3_collectorInsertAndMakeBase_60(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + mexAtExit(&_deleteAllObjects); + typedef boost::shared_ptr Shared; + + Shared *self = *reinterpret_cast (mxGetData(in[0])); + collector_MyTemplatePoint3.insert(self); + + typedef boost::shared_ptr SharedBase; + out[0] = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL); + *reinterpret_cast(mxGetData(out[0])) = new SharedBase(*self); +} + +void MyTemplatePoint3_upcastFromVoid_61(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 MyTemplatePoint3_constructor_62(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + mexAtExit(&_deleteAllObjects); + typedef boost::shared_ptr Shared; + + Shared *self = new Shared(new MyTemplatePoint3()); + collector_MyTemplatePoint3.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 MyTemplatePoint3_deconstructor_63(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + typedef boost::shared_ptr Shared; + checkArguments("delete_MyTemplatePoint3",nargout,nargin,1); + Shared *self = *reinterpret_cast(mxGetData(in[0])); + Collector_MyTemplatePoint3::iterator item; + item = collector_MyTemplatePoint3.find(self); + if(item != collector_MyTemplatePoint3.end()) { + delete self; + collector_MyTemplatePoint3.erase(item); + } +} + +void MyTemplatePoint3_accept_T_64(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + typedef boost::shared_ptr Shared; + checkArguments("accept_T",nargout,nargin-1,1); + Shared obj = unwrap_shared_ptr(in[0], "ptr_MyTemplatePoint3"); + gtsam::Point3& value = *unwrap_shared_ptr< gtsam::Point3 >(in[1], "ptr_gtsamPoint3"); + obj->accept_T(value); +} + +void MyTemplatePoint3_accept_Tptr_65(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + typedef boost::shared_ptr Shared; + checkArguments("accept_Tptr",nargout,nargin-1,1); + Shared obj = unwrap_shared_ptr(in[0], "ptr_MyTemplatePoint3"); + boost::shared_ptr value = unwrap_shared_ptr< gtsam::Point3 >(in[1], "ptr_gtsamPoint3"); + obj->accept_Tptr(value); +} + +void MyTemplatePoint3_create_MixedPtrs_66(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + typedef boost::shared_ptr SharedPoint3; + typedef boost::shared_ptr SharedPoint3; + typedef boost::shared_ptr Shared; + checkArguments("create_MixedPtrs",nargout,nargin-1,0); + Shared obj = unwrap_shared_ptr(in[0], "ptr_MyTemplatePoint3"); + pair< gtsam::Point3, SharedPoint3 > pairResult = obj->create_MixedPtrs(); + out[0] = wrap_shared_ptr(SharedPoint3(new gtsam::Point3(pairResult.first)),"gtsam.Point3", false); + out[1] = wrap_shared_ptr(pairResult.second,"gtsam.Point3", false); +} + +void MyTemplatePoint3_create_ptrs_67(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + typedef boost::shared_ptr SharedPoint3; + typedef boost::shared_ptr SharedPoint3; + typedef boost::shared_ptr Shared; + checkArguments("create_ptrs",nargout,nargin-1,0); + Shared obj = unwrap_shared_ptr(in[0], "ptr_MyTemplatePoint3"); + pair< SharedPoint3, SharedPoint3 > pairResult = obj->create_ptrs(); + out[0] = wrap_shared_ptr(pairResult.first,"gtsam.Point3", false); + out[1] = wrap_shared_ptr(pairResult.second,"gtsam.Point3", false); +} + +void MyTemplatePoint3_return_T_68(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + typedef boost::shared_ptr SharedPoint3; + typedef boost::shared_ptr Shared; + checkArguments("return_T",nargout,nargin-1,1); + Shared obj = unwrap_shared_ptr(in[0], "ptr_MyTemplatePoint3"); + boost::shared_ptr value = unwrap_shared_ptr< gtsam::Point3 >(in[1], "ptr_gtsamPoint3"); + out[0] = wrap_shared_ptr(SharedPoint3(new gtsam::Point3(obj->return_T(value))),"gtsam.Point3", false); +} + +void MyTemplatePoint3_return_Tptr_69(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + typedef boost::shared_ptr SharedPoint3; + typedef boost::shared_ptr Shared; + checkArguments("return_Tptr",nargout,nargin-1,1); + Shared obj = unwrap_shared_ptr(in[0], "ptr_MyTemplatePoint3"); + boost::shared_ptr value = unwrap_shared_ptr< gtsam::Point3 >(in[1], "ptr_gtsamPoint3"); + out[0] = wrap_shared_ptr(obj->return_Tptr(value),"gtsam.Point3", false); +} + +void MyTemplatePoint3_return_ptrs_70(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + typedef boost::shared_ptr SharedPoint3; + typedef boost::shared_ptr SharedPoint3; + typedef boost::shared_ptr Shared; + checkArguments("return_ptrs",nargout,nargin-1,2); + Shared obj = unwrap_shared_ptr(in[0], "ptr_MyTemplatePoint3"); + boost::shared_ptr p1 = unwrap_shared_ptr< gtsam::Point3 >(in[1], "ptr_gtsamPoint3"); + boost::shared_ptr p2 = unwrap_shared_ptr< gtsam::Point3 >(in[2], "ptr_gtsamPoint3"); + pair< SharedPoint3, SharedPoint3 > pairResult = obj->return_ptrs(p1,p2); + out[0] = wrap_shared_ptr(pairResult.first,"gtsam.Point3", false); + out[1] = wrap_shared_ptr(pairResult.second,"gtsam.Point3", false); +} + +void MyTemplatePoint3_templatedMethod_71(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + typedef boost::shared_ptr Shared; + checkArguments("templatedMethodMatrix",nargout,nargin-1,1); + Shared obj = unwrap_shared_ptr(in[0], "ptr_MyTemplatePoint3"); + Matrix& t = *unwrap_shared_ptr< Matrix >(in[1], "ptr_Matrix"); + obj->templatedMethod(t); +} + +void MyTemplatePoint3_templatedMethod_72(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + typedef boost::shared_ptr Shared; + checkArguments("templatedMethodPoint2",nargout,nargin-1,1); + Shared obj = unwrap_shared_ptr(in[0], "ptr_MyTemplatePoint3"); + gtsam::Point2& t = *unwrap_shared_ptr< gtsam::Point2 >(in[1], "ptr_gtsamPoint2"); + obj->templatedMethod(t); +} + +void MyTemplatePoint3_templatedMethod_73(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + typedef boost::shared_ptr Shared; + checkArguments("templatedMethodPoint3",nargout,nargin-1,1); + Shared obj = unwrap_shared_ptr(in[0], "ptr_MyTemplatePoint3"); + gtsam::Point3& t = *unwrap_shared_ptr< gtsam::Point3 >(in[1], "ptr_gtsamPoint3"); + obj->templatedMethod(t); +} + +void MyTemplatePoint3_templatedMethod_74(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + typedef boost::shared_ptr Shared; + checkArguments("templatedMethodVector",nargout,nargin-1,1); + Shared obj = unwrap_shared_ptr(in[0], "ptr_MyTemplatePoint3"); + Vector& t = *unwrap_shared_ptr< Vector >(in[1], "ptr_Vector"); + obj->templatedMethod(t); +} + +void MyFactorPosePoint2_collectorInsertAndMakeBase_75(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_76(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 MyFactorPosePoint2(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_77(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 aGlobalFunction_78(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { checkArguments("aGlobalFunction",nargout,nargin,0); out[0] = wrap< Vector >(aGlobalFunction()); } -void overloadedGlobalFunction_43(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void overloadedGlobalFunction_79(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_44(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void overloadedGlobalFunction_80(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { checkArguments("overloadedGlobalFunction",nargout,nargin,2); int a = unwrap< int >(in[0]); @@ -528,61 +958,61 @@ void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) try { switch(id) { case 0: - Point2_collectorInsertAndMakeBase_0(nargout, out, nargin-1, in+1); + gtsamPoint2_collectorInsertAndMakeBase_0(nargout, out, nargin-1, in+1); break; case 1: - Point2_constructor_1(nargout, out, nargin-1, in+1); + gtsamPoint2_constructor_1(nargout, out, nargin-1, in+1); break; case 2: - Point2_constructor_2(nargout, out, nargin-1, in+1); + gtsamPoint2_constructor_2(nargout, out, nargin-1, in+1); break; case 3: - Point2_deconstructor_3(nargout, out, nargin-1, in+1); + gtsamPoint2_deconstructor_3(nargout, out, nargin-1, in+1); break; case 4: - Point2_argChar_4(nargout, out, nargin-1, in+1); + gtsamPoint2_argChar_4(nargout, out, nargin-1, in+1); break; case 5: - Point2_argUChar_5(nargout, out, nargin-1, in+1); + gtsamPoint2_argUChar_5(nargout, out, nargin-1, in+1); break; case 6: - Point2_dim_6(nargout, out, nargin-1, in+1); + gtsamPoint2_dim_6(nargout, out, nargin-1, in+1); break; case 7: - Point2_returnChar_7(nargout, out, nargin-1, in+1); + gtsamPoint2_returnChar_7(nargout, out, nargin-1, in+1); break; case 8: - Point2_vectorConfusion_8(nargout, out, nargin-1, in+1); + gtsamPoint2_vectorConfusion_8(nargout, out, nargin-1, in+1); break; case 9: - Point2_x_9(nargout, out, nargin-1, in+1); + gtsamPoint2_x_9(nargout, out, nargin-1, in+1); break; case 10: - Point2_y_10(nargout, out, nargin-1, in+1); + gtsamPoint2_y_10(nargout, out, nargin-1, in+1); break; case 11: - Point3_collectorInsertAndMakeBase_11(nargout, out, nargin-1, in+1); + gtsamPoint3_collectorInsertAndMakeBase_11(nargout, out, nargin-1, in+1); break; case 12: - Point3_constructor_12(nargout, out, nargin-1, in+1); + gtsamPoint3_constructor_12(nargout, out, nargin-1, in+1); break; case 13: - Point3_deconstructor_13(nargout, out, nargin-1, in+1); + gtsamPoint3_deconstructor_13(nargout, out, nargin-1, in+1); break; case 14: - Point3_norm_14(nargout, out, nargin-1, in+1); + gtsamPoint3_norm_14(nargout, out, nargin-1, in+1); break; case 15: - Point3_string_serialize_15(nargout, out, nargin-1, in+1); + gtsamPoint3_string_serialize_15(nargout, out, nargin-1, in+1); break; case 16: - Point3_StaticFunctionRet_16(nargout, out, nargin-1, in+1); + gtsamPoint3_StaticFunctionRet_16(nargout, out, nargin-1, in+1); break; case 17: - Point3_staticFunction_17(nargout, out, nargin-1, in+1); + gtsamPoint3_staticFunction_17(nargout, out, nargin-1, in+1); break; case 18: - Point3_string_deserialize_18(nargout, out, nargin-1, in+1); + gtsamPoint3_string_deserialize_18(nargout, out, nargin-1, in+1); break; case 19: Test_collectorInsertAndMakeBase_19(nargout, out, nargin-1, in+1); @@ -654,13 +1084,121 @@ void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) Test_return_vector2_41(nargout, out, nargin-1, in+1); break; case 42: - aGlobalFunction_42(nargout, out, nargin-1, in+1); + MyBase_collectorInsertAndMakeBase_42(nargout, out, nargin-1, in+1); break; case 43: - overloadedGlobalFunction_43(nargout, out, nargin-1, in+1); + MyBase_upcastFromVoid_43(nargout, out, nargin-1, in+1); break; case 44: - overloadedGlobalFunction_44(nargout, out, nargin-1, in+1); + MyBase_deconstructor_44(nargout, out, nargin-1, in+1); + break; + case 45: + MyTemplatePoint2_collectorInsertAndMakeBase_45(nargout, out, nargin-1, in+1); + break; + case 46: + MyTemplatePoint2_upcastFromVoid_46(nargout, out, nargin-1, in+1); + break; + case 47: + MyTemplatePoint2_constructor_47(nargout, out, nargin-1, in+1); + break; + case 48: + MyTemplatePoint2_deconstructor_48(nargout, out, nargin-1, in+1); + break; + case 49: + MyTemplatePoint2_accept_T_49(nargout, out, nargin-1, in+1); + break; + case 50: + MyTemplatePoint2_accept_Tptr_50(nargout, out, nargin-1, in+1); + break; + case 51: + MyTemplatePoint2_create_MixedPtrs_51(nargout, out, nargin-1, in+1); + break; + case 52: + MyTemplatePoint2_create_ptrs_52(nargout, out, nargin-1, in+1); + break; + case 53: + MyTemplatePoint2_return_T_53(nargout, out, nargin-1, in+1); + break; + case 54: + MyTemplatePoint2_return_Tptr_54(nargout, out, nargin-1, in+1); + break; + case 55: + MyTemplatePoint2_return_ptrs_55(nargout, out, nargin-1, in+1); + break; + case 56: + MyTemplatePoint2_templatedMethod_56(nargout, out, nargin-1, in+1); + break; + case 57: + MyTemplatePoint2_templatedMethod_57(nargout, out, nargin-1, in+1); + break; + case 58: + MyTemplatePoint2_templatedMethod_58(nargout, out, nargin-1, in+1); + break; + case 59: + MyTemplatePoint2_templatedMethod_59(nargout, out, nargin-1, in+1); + break; + case 60: + MyTemplatePoint3_collectorInsertAndMakeBase_60(nargout, out, nargin-1, in+1); + break; + case 61: + MyTemplatePoint3_upcastFromVoid_61(nargout, out, nargin-1, in+1); + break; + case 62: + MyTemplatePoint3_constructor_62(nargout, out, nargin-1, in+1); + break; + case 63: + MyTemplatePoint3_deconstructor_63(nargout, out, nargin-1, in+1); + break; + case 64: + MyTemplatePoint3_accept_T_64(nargout, out, nargin-1, in+1); + break; + case 65: + MyTemplatePoint3_accept_Tptr_65(nargout, out, nargin-1, in+1); + break; + case 66: + MyTemplatePoint3_create_MixedPtrs_66(nargout, out, nargin-1, in+1); + break; + case 67: + MyTemplatePoint3_create_ptrs_67(nargout, out, nargin-1, in+1); + break; + case 68: + MyTemplatePoint3_return_T_68(nargout, out, nargin-1, in+1); + break; + case 69: + MyTemplatePoint3_return_Tptr_69(nargout, out, nargin-1, in+1); + break; + case 70: + MyTemplatePoint3_return_ptrs_70(nargout, out, nargin-1, in+1); + break; + case 71: + MyTemplatePoint3_templatedMethod_71(nargout, out, nargin-1, in+1); + break; + case 72: + MyTemplatePoint3_templatedMethod_72(nargout, out, nargin-1, in+1); + break; + case 73: + MyTemplatePoint3_templatedMethod_73(nargout, out, nargin-1, in+1); + break; + case 74: + MyTemplatePoint3_templatedMethod_74(nargout, out, nargin-1, in+1); + break; + case 75: + MyFactorPosePoint2_collectorInsertAndMakeBase_75(nargout, out, nargin-1, in+1); + break; + case 76: + MyFactorPosePoint2_constructor_76(nargout, out, nargin-1, in+1); + break; + case 77: + MyFactorPosePoint2_deconstructor_77(nargout, out, nargin-1, in+1); + break; + case 78: + aGlobalFunction_78(nargout, out, nargin-1, in+1); + break; + case 79: + overloadedGlobalFunction_79(nargout, out, nargin-1, in+1); + break; + case 80: + overloadedGlobalFunction_80(nargout, out, nargin-1, in+1); break; } } catch(const std::exception& e) { diff --git a/wrap/tests/expected/overloadedGlobalFunction.m b/wrap/tests/expected/overloadedGlobalFunction.m index 5b086b15e..04b12e081 100644 --- a/wrap/tests/expected/overloadedGlobalFunction.m +++ b/wrap/tests/expected/overloadedGlobalFunction.m @@ -1,8 +1,8 @@ function varargout = overloadedGlobalFunction(varargin) if length(varargin) == 1 && isa(varargin{1},'numeric') - varargout{1} = geometry_wrapper(43, varargin{:}); + varargout{1} = geometry_wrapper(79, varargin{:}); elseif length(varargin) == 2 && isa(varargin{1},'numeric') && isa(varargin{2},'double') - varargout{1} = geometry_wrapper(44, varargin{:}); + varargout{1} = geometry_wrapper(80, varargin{:}); else error('Arguments do not match any overload of function overloadedGlobalFunction'); end From 1fd0f964eadea2bb71e7a816112e76fdd7481947 Mon Sep 17 00:00:00 2001 From: dellaert Date: Sat, 29 Nov 2014 13:53:59 +0100 Subject: [PATCH 014/126] Allow Eigen type in typedefs --- wrap/Module.cpp | 2 +- wrap/tests/expected/geometry_wrapper.cpp | 2 +- wrap/tests/geometry.h | 2 +- 3 files changed, 3 insertions(+), 3 deletions(-) diff --git a/wrap/Module.cpp b/wrap/Module.cpp index ee1e78742..277845889 100644 --- a/wrap/Module.cpp +++ b/wrap/Module.cpp @@ -178,7 +178,7 @@ void Module::parseMarkup(const std::string& data) { TemplateInstantiationTypedef singleInstantiation; Rule templateSingleInstantiationArg_p = (*(namespace_name_p[push_back_a(templateArgValue.namespaces)] >> str_p("::")) >> - className_p[assign_a(templateArgValue.name)]) + (className_p | eigenType_p)[assign_a(templateArgValue.name)]) [push_back_a(singleInstantiation.typeList, templateArgValue)] [clear_a(templateArgValue)]; diff --git a/wrap/tests/expected/geometry_wrapper.cpp b/wrap/tests/expected/geometry_wrapper.cpp index 158e326bc..52eb42efd 100644 --- a/wrap/tests/expected/geometry_wrapper.cpp +++ b/wrap/tests/expected/geometry_wrapper.cpp @@ -10,7 +10,7 @@ typedef MyTemplate MyTemplatePoint2; typedef MyTemplate MyTemplatePoint3; -typedef MyFactor MyFactorPosePoint2; +typedef MyFactor MyFactorPosePoint2; BOOST_CLASS_EXPORT_GUID(gtsam::Point2, "gtsamPoint2"); BOOST_CLASS_EXPORT_GUID(gtsam::Point3, "gtsamPoint3"); diff --git a/wrap/tests/geometry.h b/wrap/tests/geometry.h index f6465fa95..c335df924 100644 --- a/wrap/tests/geometry.h +++ b/wrap/tests/geometry.h @@ -124,7 +124,7 @@ class MyFactor { }; // and a typedef specializing it -typedef MyFactor MyFactorPosePoint2; +typedef MyFactor MyFactorPosePoint2; // comments at the end! From ea070353d67ab3bedd916de1eca8f4672c6d50d5 Mon Sep 17 00:00:00 2001 From: dellaert Date: Sat, 29 Nov 2014 13:59:23 +0100 Subject: [PATCH 015/126] non-serialization expected values --- wrap/tests/expected2/geometry_wrapper.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/wrap/tests/expected2/geometry_wrapper.cpp b/wrap/tests/expected2/geometry_wrapper.cpp index 77559f3da..22e1cf11a 100644 --- a/wrap/tests/expected2/geometry_wrapper.cpp +++ b/wrap/tests/expected2/geometry_wrapper.cpp @@ -6,7 +6,7 @@ typedef MyTemplate MyTemplatePoint2; typedef MyTemplate MyTemplatePoint3; -typedef MyFactor MyFactorPosePoint2; +typedef MyFactor MyFactorPosePoint2; typedef std::set*> Collector_gtsamPoint2; static Collector_gtsamPoint2 collector_gtsamPoint2; From 63918ff7de29ff410782a0b0c76b87030ec99314 Mon Sep 17 00:00:00 2001 From: dellaert Date: Sat, 29 Nov 2014 15:06:26 +0100 Subject: [PATCH 016/126] Now dynamically sized matrices live in manifolds, too. --- gtsam/base/Manifold.h | 57 +++++++++++++++++++--------- gtsam/nonlinear/tests/testValues.cpp | 8 ++-- 2 files changed, 44 insertions(+), 21 deletions(-) diff --git a/gtsam/base/Manifold.h b/gtsam/base/Manifold.h index a3a5b029b..1190822ed 100644 --- a/gtsam/base/Manifold.h +++ b/gtsam/base/Manifold.h @@ -73,7 +73,6 @@ template struct dimension: public Dynamic { }; - /** * zero::value is intended to be the origin of a canonical coordinate system * with canonical(t) == DefaultChart::local(zero::value, t) @@ -111,14 +110,16 @@ struct is_group > : publi }; template -struct is_manifold > : public boost::true_type{ +struct is_manifold > : public boost::true_type { }; template -struct dimension > : public boost::integral_constant { - //TODO after switch to c++11 : the above should should be extracted to a constexpr function - // for readability and to reduce code duplication +struct dimension > : public boost::integral_constant< + int, + M == Eigen::Dynamic ? Eigen::Dynamic : + (N == Eigen::Dynamic ? Eigen::Dynamic : M * N)> { + //TODO after switch to c++11 : the above should should be extracted to a constexpr function + // for readability and to reduce code duplication }; template @@ -131,10 +132,10 @@ struct zero > { }; template -struct identity > : public zero > { +struct identity > : public zero< + Eigen::Matrix > { }; - template struct is_chart: public boost::false_type { }; @@ -248,12 +249,16 @@ struct DefaultChart > { * This chart for the vector space of M x N matrices (represented by Eigen matrices) chooses as basis the one with respect to which the coordinates are exactly the matrix entries as laid out in memory (as determined by Options). * Computing coordinates for a matrix is then simply a reshape to the row vector of appropriate size. */ - typedef Eigen::Matrix type; + typedef Eigen::Matrix type; typedef type T; - typedef Eigen::Matrix::value, 1> vector;BOOST_STATIC_ASSERT_MSG((M!=Eigen::Dynamic && N!=Eigen::Dynamic), - "DefaultChart has not been implemented yet for dynamically sized matrices"); + typedef Eigen::Matrix::value, 1> vector; + + BOOST_STATIC_ASSERT_MSG((M!=Eigen::Dynamic && N!=Eigen::Dynamic), + "Internal error: DefaultChart for Dynamic should be handled by template below"); + static vector local(const T& origin, const T& other) { - return reshape(other) - reshape(origin); + return reshape(other) + - reshape(origin); } static T retract(const T& origin, const vector& d) { return origin + reshape(d); @@ -266,20 +271,36 @@ struct DefaultChart > { // Dynamically sized Vector template<> struct DefaultChart { - typedef Vector T; - typedef T type; - typedef T vector; - static vector local(const T& origin, const T& other) { + typedef Vector type; + typedef Vector vector; + static vector local(const Vector& origin, const Vector& other) { return other - origin; } - static T retract(const T& origin, const vector& d) { + static Vector retract(const Vector& origin, const vector& d) { return origin + d; } - static int getDimension(const T& origin) { + static int getDimension(const Vector& origin) { return origin.size(); } }; +// Dynamically sized Matrix +template<> +struct DefaultChart { + typedef Matrix type; + typedef Vector vector; + static vector local(const Matrix& origin, const Matrix& other) { + Matrix d = other - origin; + return Eigen::Map(d.data(),getDimension(d)); + } + static Matrix retract(const Matrix& origin, const vector& d) { + return origin + Eigen::Map(d.data(),origin.rows(),origin.cols()); + } + static int getDimension(const Matrix& m) { + return m.size(); + } +}; + /** * Old Concept check class for Manifold types * Requires a mapping between a linear tangent space and the underlying diff --git a/gtsam/nonlinear/tests/testValues.cpp b/gtsam/nonlinear/tests/testValues.cpp index 09fe0f253..941728d8c 100644 --- a/gtsam/nonlinear/tests/testValues.cpp +++ b/gtsam/nonlinear/tests/testValues.cpp @@ -12,6 +12,8 @@ /** * @file testValues.cpp * @author Richard Roberts + * @author Frank Dellaert + * @author Mike Bosse */ #include @@ -168,9 +170,9 @@ TEST(Values, basic_functions) Values values; const Values& values_c = values; values.insert(2, Vector3()); - values.insert(4, Vector3()); - values.insert(6, Vector3()); - values.insert(8, Vector3()); + values.insert(4, Vector(3)); + values.insert(6, Matrix23()); + values.insert(8, Matrix(2,3)); // find EXPECT_LONGS_EQUAL(4, values.find(4)->key); From 6c0439f6eafcda0fa1dd4a0cc8f26959d47c6c83 Mon Sep 17 00:00:00 2001 From: dellaert Date: Sat, 29 Nov 2014 15:31:29 +0100 Subject: [PATCH 017/126] Method and StaticMethod now inherit from MethodBase - much better --- wrap/Method.cpp | 2 +- wrap/Method.h | 4 +- wrap/MethodBase.cpp | 145 ++++++++++++++++++++++++++++++++++++++++++ wrap/MethodBase.h | 72 +++++++++++++++++++++ wrap/StaticMethod.cpp | 115 +-------------------------------- wrap/StaticMethod.h | 32 +--------- 6 files changed, 223 insertions(+), 147 deletions(-) create mode 100644 wrap/MethodBase.cpp create mode 100644 wrap/MethodBase.h diff --git a/wrap/Method.cpp b/wrap/Method.cpp index 1feb0f70f..0bded5f60 100644 --- a/wrap/Method.cpp +++ b/wrap/Method.cpp @@ -32,7 +32,7 @@ using namespace wrap; bool Method::addOverload(Str name, const ArgumentList& args, const ReturnValue& retVal, bool is_const, const Qualified& instName, bool verbose) { - bool first = StaticMethod::addOverload(name, args, retVal, instName, verbose); + bool first = MethodBase::addOverload(name, args, retVal, instName, verbose); if (first) is_const_ = is_const; else if (is_const && !is_const_) diff --git a/wrap/Method.h b/wrap/Method.h index db9e6bb9f..e0e19c656 100644 --- a/wrap/Method.h +++ b/wrap/Method.h @@ -18,12 +18,12 @@ #pragma once -#include "StaticMethod.h" +#include "MethodBase.h" namespace wrap { /// Method class -class Method: public StaticMethod { +class Method: public MethodBase { bool is_const_; diff --git a/wrap/MethodBase.cpp b/wrap/MethodBase.cpp new file mode 100644 index 000000000..6f0d4d82d --- /dev/null +++ b/wrap/MethodBase.cpp @@ -0,0 +1,145 @@ +/* ---------------------------------------------------------------------------- + + * GTSAM Copyright 2010, Georgia Tech Research Corporation, + * Atlanta, Georgia 30332-0415 + * All Rights Reserved + * Authors: Frank Dellaert, et al. (see THANKS for the full author list) + + * See LICENSE for the license information + + * -------------------------------------------------------------------------- */ + +/** + * @file MethodBase.ccp + * @author Frank Dellaert + * @author Andrew Melim + * @author Richard Roberts + **/ + +#include "Method.h" +#include "utilities.h" + +#include +#include +#include + +#include +#include + +using namespace std; +using namespace wrap; + +/* ************************************************************************* */ +void MethodBase::proxy_wrapper_fragments(FileWriter& proxyFile, + FileWriter& wrapperFile, Str cppClassName, Str matlabQualName, + Str matlabUniqueName, Str wrapperName, + const TypeAttributesTable& typeAttributes, + vector& functionNames) const { + + // emit header, e.g., function varargout = templatedMethod(this, varargin) + proxy_header(proxyFile); + + // Emit comments for documentation + string up_name = boost::to_upper_copy(matlabName()); + proxyFile.oss << " % " << up_name << " usage: "; + usage_fragment(proxyFile, matlabName()); + + // Emit URL to Doxygen page + proxyFile.oss << " % " + << "Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html" + << endl; + + // Handle special case of single overload with all numeric arguments + if (nrOverloads() == 1 && argumentList(0).allScalar()) { + // Output proxy matlab code + // TODO: document why is it OK to not check arguments in this case + proxyFile.oss << " "; + const int id = (int) functionNames.size(); + argumentList(0).emit_call(proxyFile, returnValue(0), wrapperName, id, + isStatic()); + + // Output C++ wrapper code + const string wrapFunctionName = wrapper_fragment(wrapperFile, cppClassName, + matlabUniqueName, 0, id, typeAttributes, templateArgValue_); + + // Add to function list + functionNames.push_back(wrapFunctionName); + } else { + // Check arguments for all overloads + for (size_t i = 0; i < nrOverloads(); ++i) { + + // Output proxy matlab code + proxyFile.oss << " " << (i == 0 ? "" : "else"); + const int id = (int) functionNames.size(); + argumentList(i).emit_conditional_call(proxyFile, returnValue(i), + wrapperName, id, isStatic()); + + // Output C++ wrapper code + const string wrapFunctionName = wrapper_fragment(wrapperFile, + cppClassName, matlabUniqueName, i, id, typeAttributes, + templateArgValue_); + + // Add to function list + functionNames.push_back(wrapFunctionName); + } + proxyFile.oss << " else\n"; + proxyFile.oss + << " error('Arguments do not match any overload of function " + << matlabQualName << "." << name_ << "');" << endl; + proxyFile.oss << " end\n"; + } + + proxyFile.oss << " end\n"; +} + +/* ************************************************************************* */ +string MethodBase::wrapper_fragment(FileWriter& wrapperFile, Str cppClassName, + Str matlabUniqueName, int overload, int id, + const TypeAttributesTable& typeAttributes, + const Qualified& instName) const { + + // generate code + + const string wrapFunctionName = matlabUniqueName + "_" + name_ + "_" + + boost::lexical_cast(id); + + const ArgumentList& args = argumentList(overload); + const ReturnValue& returnVal = returnValue(overload); + + // call + wrapperFile.oss << "void " << wrapFunctionName + << "(int nargout, mxArray *out[], int nargin, const mxArray *in[])\n"; + // start + wrapperFile.oss << "{\n"; + + returnVal.wrapTypeUnwrap(wrapperFile); + + wrapperFile.oss << " typedef boost::shared_ptr<" << cppClassName + << "> Shared;" << endl; + + // get call + // for static methods: cppClassName::staticMethod + // for instance methods: obj->instanceMethod + string expanded = wrapper_call(wrapperFile, cppClassName, matlabUniqueName, + args, returnVal, typeAttributes, instName); + + expanded += ("(" + args.names() + ")"); + if (returnVal.type1.name != "void") + returnVal.wrap_result(expanded, wrapperFile, typeAttributes); + else + wrapperFile.oss << " " + expanded + ";\n"; + + // finish + wrapperFile.oss << "}\n"; + + return wrapFunctionName; +} + +/* ************************************************************************* */ +void MethodBase::python_wrapper(FileWriter& wrapperFile, + Str className) const { + wrapperFile.oss << " .def(\"" << name_ << "\", &" << className << "::" << name_ + << ");\n"; +} + +/* ************************************************************************* */ diff --git a/wrap/MethodBase.h b/wrap/MethodBase.h new file mode 100644 index 000000000..d14e632d3 --- /dev/null +++ b/wrap/MethodBase.h @@ -0,0 +1,72 @@ +/* ---------------------------------------------------------------------------- + + * GTSAM Copyright 2010, Georgia Tech Research Corporation, + * Atlanta, Georgia 30332-0415 + * All Rights Reserved + * Authors: Frank Dellaert, et al. (see THANKS for the full author list) + + * See LICENSE for the license information + + * -------------------------------------------------------------------------- */ + +/** + * @file MethodBase.h + * @brief describes and generates code for static methods + * @author Frank Dellaert + * @author Alex Cunningham + * @author Richard Roberts + **/ + +#pragma once + +#include "FullyOverloadedFunction.h" + +namespace wrap { + +/// MethodBase class +struct MethodBase: public FullyOverloadedFunction { + + typedef const std::string& Str; + + virtual bool isStatic() const = 0; + + // emit a list of comments, one for each overload + void comment_fragment(FileWriter& proxyFile) const { + SignatureOverloads::comment_fragment(proxyFile, matlabName()); + } + + void verifyArguments(const std::vector& validArgs) const { + SignatureOverloads::verifyArguments(validArgs, name_); + } + + void verifyReturnTypes(const std::vector& validtypes) const { + SignatureOverloads::verifyReturnTypes(validtypes, name_); + } + + // MATLAB code generation + // classPath is class directory, e.g., ../matlab/@Point2 + void proxy_wrapper_fragments(FileWriter& proxyFile, FileWriter& wrapperFile, + Str cppClassName, Str matlabQualName, Str matlabUniqueName, + Str wrapperName, const TypeAttributesTable& typeAttributes, + std::vector& functionNames) const; + + // emit python wrapper + void python_wrapper(FileWriter& wrapperFile, Str className) const; + +protected: + + virtual void proxy_header(FileWriter& proxyFile) const = 0; + + std::string wrapper_fragment(FileWriter& wrapperFile, Str cppClassName, + Str matlabUniqueName, int overload, int id, + const TypeAttributesTable& typeAttributes, const Qualified& instName = + Qualified()) const; ///< cpp wrapper + + virtual std::string wrapper_call(FileWriter& wrapperFile, Str cppClassName, + Str matlabUniqueName, const ArgumentList& args, + const ReturnValue& returnVal, const TypeAttributesTable& typeAttributes, + const Qualified& instName) const = 0; +}; + +} // \namespace wrap + diff --git a/wrap/StaticMethod.cpp b/wrap/StaticMethod.cpp index 5f91a15b4..9ecc1ca56 100644 --- a/wrap/StaticMethod.cpp +++ b/wrap/StaticMethod.cpp @@ -16,7 +16,7 @@ * @author Richard Roberts **/ -#include "Method.h" +#include "StaticMethod.h" #include "utilities.h" #include @@ -36,112 +36,6 @@ void StaticMethod::proxy_header(FileWriter& proxyFile) const { proxyFile.oss << " function varargout = " << upperName << "(varargin)\n"; } -/* ************************************************************************* */ -void StaticMethod::proxy_wrapper_fragments(FileWriter& proxyFile, - FileWriter& wrapperFile, Str cppClassName, Str matlabQualName, - Str matlabUniqueName, Str wrapperName, - const TypeAttributesTable& typeAttributes, - vector& functionNames) const { - - // emit header, e.g., function varargout = templatedMethod(this, varargin) - proxy_header(proxyFile); - - // Emit comments for documentation - string up_name = boost::to_upper_copy(matlabName()); - proxyFile.oss << " % " << up_name << " usage: "; - usage_fragment(proxyFile, matlabName()); - - // Emit URL to Doxygen page - proxyFile.oss << " % " - << "Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html" - << endl; - - // Handle special case of single overload with all numeric arguments - if (nrOverloads() == 1 && argumentList(0).allScalar()) { - // Output proxy matlab code - // TODO: document why is it OK to not check arguments in this case - proxyFile.oss << " "; - const int id = (int) functionNames.size(); - argumentList(0).emit_call(proxyFile, returnValue(0), wrapperName, id, - isStatic()); - - // Output C++ wrapper code - const string wrapFunctionName = wrapper_fragment(wrapperFile, cppClassName, - matlabUniqueName, 0, id, typeAttributes, templateArgValue_); - - // Add to function list - functionNames.push_back(wrapFunctionName); - } else { - // Check arguments for all overloads - for (size_t i = 0; i < nrOverloads(); ++i) { - - // Output proxy matlab code - proxyFile.oss << " " << (i == 0 ? "" : "else"); - const int id = (int) functionNames.size(); - argumentList(i).emit_conditional_call(proxyFile, returnValue(i), - wrapperName, id, isStatic()); - - // Output C++ wrapper code - const string wrapFunctionName = wrapper_fragment(wrapperFile, - cppClassName, matlabUniqueName, i, id, typeAttributes, - templateArgValue_); - - // Add to function list - functionNames.push_back(wrapFunctionName); - } - proxyFile.oss << " else\n"; - proxyFile.oss - << " error('Arguments do not match any overload of function " - << matlabQualName << "." << name_ << "');" << endl; - proxyFile.oss << " end\n"; - } - - proxyFile.oss << " end\n"; -} - -/* ************************************************************************* */ -string StaticMethod::wrapper_fragment(FileWriter& wrapperFile, Str cppClassName, - Str matlabUniqueName, int overload, int id, - const TypeAttributesTable& typeAttributes, - const Qualified& instName) const { - - // generate code - - const string wrapFunctionName = matlabUniqueName + "_" + name_ + "_" - + boost::lexical_cast(id); - - const ArgumentList& args = argumentList(overload); - const ReturnValue& returnVal = returnValue(overload); - - // call - wrapperFile.oss << "void " << wrapFunctionName - << "(int nargout, mxArray *out[], int nargin, const mxArray *in[])\n"; - // start - wrapperFile.oss << "{\n"; - - returnVal.wrapTypeUnwrap(wrapperFile); - - wrapperFile.oss << " typedef boost::shared_ptr<" << cppClassName - << "> Shared;" << endl; - - // get call - // for static methods: cppClassName::staticMethod - // for instance methods: obj->instanceMethod - string expanded = wrapper_call(wrapperFile, cppClassName, matlabUniqueName, - args, returnVal, typeAttributes, instName); - - expanded += ("(" + args.names() + ")"); - if (returnVal.type1.name != "void") - returnVal.wrap_result(expanded, wrapperFile, typeAttributes); - else - wrapperFile.oss << " " + expanded + ";\n"; - - // finish - wrapperFile.oss << "}\n"; - - return wrapFunctionName; -} - /* ************************************************************************* */ string StaticMethod::wrapper_call(FileWriter& wrapperFile, Str cppClassName, Str matlabUniqueName, const ArgumentList& args, @@ -165,10 +59,3 @@ string StaticMethod::wrapper_call(FileWriter& wrapperFile, Str cppClassName, } /* ************************************************************************* */ -void StaticMethod::python_wrapper(FileWriter& wrapperFile, - Str className) const { - wrapperFile.oss << " .def(\"" << name_ << "\", &" << className << "::" << name_ - << ");\n"; -} - -/* ************************************************************************* */ diff --git a/wrap/StaticMethod.h b/wrap/StaticMethod.h index de8e4a94e..73cb66c65 100644 --- a/wrap/StaticMethod.h +++ b/wrap/StaticMethod.h @@ -19,12 +19,12 @@ #pragma once -#include "FullyOverloadedFunction.h" +#include "MethodBase.h" namespace wrap { /// StaticMethod class -struct StaticMethod: public FullyOverloadedFunction { +struct StaticMethod: public MethodBase { typedef const std::string& Str; @@ -32,29 +32,6 @@ struct StaticMethod: public FullyOverloadedFunction { return true; } - // emit a list of comments, one for each overload - void comment_fragment(FileWriter& proxyFile) const { - SignatureOverloads::comment_fragment(proxyFile, matlabName()); - } - - void verifyArguments(const std::vector& validArgs) const { - SignatureOverloads::verifyArguments(validArgs, name_); - } - - void verifyReturnTypes(const std::vector& validtypes) const { - SignatureOverloads::verifyReturnTypes(validtypes, name_); - } - - // MATLAB code generation - // classPath is class directory, e.g., ../matlab/@Point2 - void proxy_wrapper_fragments(FileWriter& proxyFile, FileWriter& wrapperFile, - Str cppClassName, Str matlabQualName, Str matlabUniqueName, - Str wrapperName, const TypeAttributesTable& typeAttributes, - std::vector& functionNames) const; - - // emit python wrapper - void python_wrapper(FileWriter& wrapperFile, Str className) const; - friend std::ostream& operator<<(std::ostream& os, const StaticMethod& m) { for (size_t i = 0; i < m.nrOverloads(); i++) os << "static " << m.returnVals_[i] << " " << m.name_ << m.argLists_[i]; @@ -65,11 +42,6 @@ protected: virtual void proxy_header(FileWriter& proxyFile) const; - std::string wrapper_fragment(FileWriter& wrapperFile, Str cppClassName, - Str matlabUniqueName, int overload, int id, - const TypeAttributesTable& typeAttributes, const Qualified& instName = - Qualified()) const; ///< cpp wrapper - virtual std::string wrapper_call(FileWriter& wrapperFile, Str cppClassName, Str matlabUniqueName, const ArgumentList& args, const ReturnValue& returnVal, const TypeAttributesTable& typeAttributes, From 6c626097378fda86ef987c739b921b373b96fc43 Mon Sep 17 00:00:00 2001 From: HannesSommer Date: Sat, 29 Nov 2014 16:03:33 +0100 Subject: [PATCH 018/126] - introduced CallRecordMaxVirtualStaticRows for keeping CallRecord.h and testCallRecord.cpp in sync with respect to this. - reactivated the fully dynamically sized matrix support in CallRecord.h - small cleanups --- gtsam_unstable/nonlinear/CallRecord.h | 17 +++++++++++++---- .../nonlinear/tests/testCallRecord.cpp | 4 ++-- 2 files changed, 15 insertions(+), 6 deletions(-) diff --git a/gtsam_unstable/nonlinear/CallRecord.h b/gtsam_unstable/nonlinear/CallRecord.h index 53eb7e845..159a841e5 100644 --- a/gtsam_unstable/nonlinear/CallRecord.h +++ b/gtsam_unstable/nonlinear/CallRecord.h @@ -99,10 +99,12 @@ struct CallRecord { jacobians); } -// TODO: remove once Hannes agrees this is never called as handled by above -// inline void reverseAD2(const Matrix & dFdT, JacobianMap& jacobians) const { -// _reverseAD3(dFdT, jacobians); -// } + // This overload supports matrices with both rows and columns dynamically sized. + // The template version above would be slower by introducing an extra conversion + // to statically sized columns. + inline void reverseAD2(const Matrix & dFdT, JacobianMap& jacobians) const { + _reverseAD3(dFdT, jacobians); + } virtual ~CallRecord() { } @@ -131,6 +133,13 @@ private: JacobianMap& jacobians) const = 0; }; +/** + * CallRecordMaxVirtualStaticRows tells which separate virtual reverseAD with specific + * static rows (1..CallRecordMaxVirtualStaticRows) methods are part of the CallRecord + * interface. It is used to keep the testCallRecord unit test in sync. + */ +const int CallRecordMaxVirtualStaticRows = 5; + namespace internal { /** * The CallRecordImplementor implements the CallRecord interface for a Derived class by diff --git a/gtsam_unstable/nonlinear/tests/testCallRecord.cpp b/gtsam_unstable/nonlinear/tests/testCallRecord.cpp index 057a870d5..1cc674901 100644 --- a/gtsam_unstable/nonlinear/tests/testCallRecord.cpp +++ b/gtsam_unstable/nonlinear/tests/testCallRecord.cpp @@ -33,7 +33,7 @@ static const int Cols = 3; int dynamicIfAboveMax(int i){ - if(i > 5){ + if(i > CallRecordMaxVirtualStaticRows){ return Eigen::Dynamic; } else return i; @@ -43,7 +43,6 @@ struct CallConfig { int compTimeCols; int runTimeRows; int runTimeCols; - CallConfig() {} CallConfig(int rows, int cols): compTimeRows(dynamicIfAboveMax(rows)), compTimeCols(cols), @@ -72,6 +71,7 @@ struct CallConfig { }; struct Record: public internal::CallRecordImplementor { + Record() : cc(0, 0) {} virtual ~Record() { } void print(const std::string& indent) const { From c68c21c18768bfefa0d1385059bf1313dfc023ed Mon Sep 17 00:00:00 2001 From: dellaert Date: Sat, 29 Nov 2014 16:13:02 +0100 Subject: [PATCH 019/126] headers --- wrap/Module.h | 9 ++++----- 1 file changed, 4 insertions(+), 5 deletions(-) diff --git a/wrap/Module.h b/wrap/Module.h index a4659dc3a..e99e77bc9 100644 --- a/wrap/Module.h +++ b/wrap/Module.h @@ -18,15 +18,15 @@ #pragma once -#include -#include -#include - #include "Class.h" #include "GlobalFunction.h" #include "TemplateInstantiationTypedef.h" #include "ForwardDeclaration.h" +#include +#include +#include + namespace wrap { /** @@ -35,7 +35,6 @@ namespace wrap { struct Module { typedef std::map GlobalFunctions; - typedef std::map Methods; // Filled during parsing: std::string name; ///< module name From c609666ab9040713846116e4da43b9b18dd73953 Mon Sep 17 00:00:00 2001 From: dellaert Date: Sat, 29 Nov 2014 16:13:23 +0100 Subject: [PATCH 020/126] More informative fail --- wrap/Class.cpp | 51 ++++++++++++++++++++++++++++++++++---------------- wrap/Class.h | 20 +++++++++++--------- 2 files changed, 46 insertions(+), 25 deletions(-) diff --git a/wrap/Class.cpp b/wrap/Class.cpp index 0e480f0fd..93135498f 100644 --- a/wrap/Class.cpp +++ b/wrap/Class.cpp @@ -22,16 +22,35 @@ #include #include +#include +#include #include #include #include +#include // std::ostream_iterator + //#include // on Linux GCC: fails with error regarding needing C++0x std flags //#include // same failure as above #include // works on Linux GCC + using namespace std; using namespace wrap; +/* ************************************************************************* */ +Method& Class::method(Str key) { + try { + return methods_.at(key); + } catch (const out_of_range& oor) { + cerr << "Class::method: key not found: " << oor.what() + << ", methods are:\n"; + using boost::adaptors::map_keys; + ostream_iterator out_it(cerr, "\n"); + boost::copy(methods_ | map_keys, out_it); + throw runtime_error("Internal error in wrap"); + } +} + /* ************************************************************************* */ void Class::matlab_proxy(Str toolboxPath, Str wrapperName, const TypeAttributesTable& typeAttributes, FileWriter& wrapperFile, @@ -111,7 +130,7 @@ void Class::matlab_proxy(Str toolboxPath, Str wrapperName, << " function disp(obj), obj.display; end\n %DISP Calls print on the object\n"; // Methods - BOOST_FOREACH(const Methods::value_type& name_m, methods) { + BOOST_FOREACH(const Methods::value_type& name_m, methods_) { const Method& m = name_m.second; m.proxy_wrapper_fragments(proxyFile, wrapperFile, cppName, matlabQualName, matlabUniqueName, wrapperName, typeAttributes, functionNames); @@ -244,7 +263,7 @@ void Class::pointer_constructor_fragments(FileWriter& proxyFile, /* ************************************************************************* */ Class Class::expandTemplate(const TemplateSubstitution& ts) const { Class inst = *this; - inst.methods = expandMethodTemplate(methods, ts); + inst.methods_ = expandMethodTemplate(methods_, ts); inst.static_methods = expandMethodTemplate(static_methods, ts); inst.constructor = constructor.expandTemplate(ts); inst.deconstructor.name = inst.name; @@ -286,36 +305,36 @@ void Class::addMethod(bool verbose, bool is_const, Str methodName, // Now stick in new overload stack with expandedMethodName key // but note we use the same, unexpanded methodName in overload string expandedMethodName = methodName + instName.name; - methods[expandedMethodName].addOverload(methodName, expandedArgs, + methods_[expandedMethodName].addOverload(methodName, expandedArgs, expandedRetVal, is_const, instName, verbose); } } else // just add overload - methods[methodName].addOverload(methodName, argumentList, returnValue, + methods_[methodName].addOverload(methodName, argumentList, returnValue, is_const, Qualified(), verbose); } /* ************************************************************************* */ void Class::erase_serialization() { - Methods::iterator it = methods.find("serializable"); - if (it != methods.end()) { + Methods::iterator it = methods_.find("serializable"); + if (it != methods_.end()) { #ifndef WRAP_DISABLE_SERIALIZE isSerializable = true; #else // cout << "Ignoring serializable() flag in class " << name << endl; #endif - methods.erase(it); + methods_.erase(it); } - it = methods.find("serialize"); - if (it != methods.end()) { + it = methods_.find("serialize"); + if (it != methods_.end()) { #ifndef WRAP_DISABLE_SERIALIZE isSerializable = true; hasSerialization = true; #else // cout << "Ignoring serialize() flag in class " << name << endl; #endif - methods.erase(it); + methods_.erase(it); } } @@ -327,11 +346,11 @@ void Class::verifyAll(vector& validTypes, bool& hasSerialiable) const { // verify all of the function arguments //TODO:verifyArguments(validTypes, constructor.args_list); verifyArguments(validTypes, static_methods); - verifyArguments(validTypes, methods); + verifyArguments(validTypes, methods_); // verify function return types verifyReturnTypes(validTypes, static_methods); - verifyReturnTypes(validTypes, methods); + verifyReturnTypes(validTypes, methods_); // verify parents if (!qualifiedParent.empty() @@ -351,7 +370,7 @@ void Class::appendInheritedMethods(const Class& cls, BOOST_FOREACH(const Class& parent, classes) { // We found a parent class for our parent, TODO improve ! if (parent.name == cls.qualifiedParent.name) { - methods.insert(parent.methods.begin(), parent.methods.end()); + methods_.insert(parent.methods_.begin(), parent.methods_.end()); appendInheritedMethods(parent, classes); } } @@ -379,9 +398,9 @@ void Class::comment_fragment(FileWriter& proxyFile) const { constructor.comment_fragment(proxyFile); - if (!methods.empty()) + if (!methods_.empty()) proxyFile.oss << "%\n%-------Methods-------\n"; - BOOST_FOREACH(const Methods::value_type& name_m, methods) + BOOST_FOREACH(const Methods::value_type& name_m, methods_) name_m.second.comment_fragment(proxyFile); if (!static_methods.empty()) @@ -590,7 +609,7 @@ void Class::python_wrapper(FileWriter& wrapperFile) const { constructor.python_wrapper(wrapperFile, name); BOOST_FOREACH(const StaticMethod& m, static_methods | boost::adaptors::map_values) m.python_wrapper(wrapperFile, name); - BOOST_FOREACH(const Method& m, methods | boost::adaptors::map_values) + BOOST_FOREACH(const Method& m, methods_ | boost::adaptors::map_values) m.python_wrapper(wrapperFile, name); wrapperFile.oss << ";\n\n"; } diff --git a/wrap/Class.h b/wrap/Class.h index 34323b797..9e4dff13d 100644 --- a/wrap/Class.h +++ b/wrap/Class.h @@ -36,13 +36,16 @@ namespace wrap { /// Class has name, constructors, methods class Class: public Qualified { + typedef const std::string& Str; + typedef std::map Methods; - Methods methods; ///< Class methods + Methods methods_; ///< Class methods public: - typedef const std::string& Str; + typedef std::map StaticMethods; + StaticMethods static_methods; ///< Static methods // Then the instance variables are set directly by the Module constructor std::vector templateArgs; ///< Template arguments @@ -51,7 +54,6 @@ public: bool isSerializable; ///< Whether we can use boost.serialization to serialize the class - creates exports bool hasSerialization; ///< Whether we should create the serialization functions Qualified qualifiedParent; ///< The *single* parent - StaticMethods static_methods; ///< Static methods Constructor constructor; ///< Class constructors Deconstructor deconstructor; ///< Deconstructor to deallocate C++ object bool verbose_; ///< verbose flag @@ -63,13 +65,13 @@ public: } size_t nrMethods() const { - return methods.size(); - } - Method& method(Str name) { - return methods.at(name); + return methods_.size(); } + + Method& method(Str key); + bool exists(Str name) const { - return methods.find(name) != methods.end(); + return methods_.find(name) != methods_.end(); } // And finally MATLAB code is emitted, methods below called by Module::matlab_code @@ -119,7 +121,7 @@ public: os << cls.constructor << ";\n"; BOOST_FOREACH(const StaticMethod& m, cls.static_methods | boost::adaptors::map_values) os << m << ";\n"; - BOOST_FOREACH(const Method& m, cls.methods | boost::adaptors::map_values) + BOOST_FOREACH(const Method& m, cls.methods_ | boost::adaptors::map_values) os << m << ";\n"; os << "};" << std::endl; return os; From b0fa5ce684d76f1c798b46570c98b21d6238391e Mon Sep 17 00:00:00 2001 From: dellaert Date: Sat, 29 Nov 2014 19:34:46 +0100 Subject: [PATCH 021/126] Cut out unused arguments --- wrap/Method.cpp | 5 ++--- wrap/Method.h | 1 - wrap/MethodBase.cpp | 9 ++++----- wrap/MethodBase.h | 1 - wrap/StaticMethod.cpp | 1 - wrap/StaticMethod.h | 1 - 6 files changed, 6 insertions(+), 12 deletions(-) diff --git a/wrap/Method.cpp b/wrap/Method.cpp index 0bded5f60..66707d7e4 100644 --- a/wrap/Method.cpp +++ b/wrap/Method.cpp @@ -53,13 +53,12 @@ void Method::proxy_header(FileWriter& proxyFile) const { /* ************************************************************************* */ string Method::wrapper_call(FileWriter& wrapperFile, Str cppClassName, Str matlabUniqueName, const ArgumentList& args, - const ReturnValue& returnVal, const TypeAttributesTable& typeAttributes, const Qualified& instName) const { // check arguments // extra argument obj -> nargin-1 is passed ! // example: checkArguments("equals",nargout,nargin-1,2); - wrapperFile.oss << " checkArguments(\"" << matlabName() << "\",nargout,nargin-1," - << args.size() << ");\n"; + wrapperFile.oss << " checkArguments(\"" << matlabName() + << "\",nargout,nargin-1," << args.size() << ");\n"; // get class pointer // example: shared_ptr = unwrap_shared_ptr< Test >(in[0], "Test"); diff --git a/wrap/Method.h b/wrap/Method.h index e0e19c656..160a0f454 100644 --- a/wrap/Method.h +++ b/wrap/Method.h @@ -56,7 +56,6 @@ private: virtual std::string wrapper_call(FileWriter& wrapperFile, Str cppClassName, Str matlabUniqueName, const ArgumentList& args, - const ReturnValue& returnVal, const TypeAttributesTable& typeAttributes, const Qualified& instName) const; }; diff --git a/wrap/MethodBase.cpp b/wrap/MethodBase.cpp index 6f0d4d82d..a63b95b90 100644 --- a/wrap/MethodBase.cpp +++ b/wrap/MethodBase.cpp @@ -121,7 +121,7 @@ string MethodBase::wrapper_fragment(FileWriter& wrapperFile, Str cppClassName, // for static methods: cppClassName::staticMethod // for instance methods: obj->instanceMethod string expanded = wrapper_call(wrapperFile, cppClassName, matlabUniqueName, - args, returnVal, typeAttributes, instName); + args, instName); expanded += ("(" + args.names() + ")"); if (returnVal.type1.name != "void") @@ -136,10 +136,9 @@ string MethodBase::wrapper_fragment(FileWriter& wrapperFile, Str cppClassName, } /* ************************************************************************* */ -void MethodBase::python_wrapper(FileWriter& wrapperFile, - Str className) const { - wrapperFile.oss << " .def(\"" << name_ << "\", &" << className << "::" << name_ - << ");\n"; +void MethodBase::python_wrapper(FileWriter& wrapperFile, Str className) const { + wrapperFile.oss << " .def(\"" << name_ << "\", &" << className << "::" + << name_ << ");\n"; } /* ************************************************************************* */ diff --git a/wrap/MethodBase.h b/wrap/MethodBase.h index d14e632d3..da50b8124 100644 --- a/wrap/MethodBase.h +++ b/wrap/MethodBase.h @@ -64,7 +64,6 @@ protected: virtual std::string wrapper_call(FileWriter& wrapperFile, Str cppClassName, Str matlabUniqueName, const ArgumentList& args, - const ReturnValue& returnVal, const TypeAttributesTable& typeAttributes, const Qualified& instName) const = 0; }; diff --git a/wrap/StaticMethod.cpp b/wrap/StaticMethod.cpp index 9ecc1ca56..6a2917eb2 100644 --- a/wrap/StaticMethod.cpp +++ b/wrap/StaticMethod.cpp @@ -39,7 +39,6 @@ void StaticMethod::proxy_header(FileWriter& proxyFile) const { /* ************************************************************************* */ string StaticMethod::wrapper_call(FileWriter& wrapperFile, Str cppClassName, Str matlabUniqueName, const ArgumentList& args, - const ReturnValue& returnVal, const TypeAttributesTable& typeAttributes, const Qualified& instName) const { // check arguments // NOTE: for static functions, there is no object passed diff --git a/wrap/StaticMethod.h b/wrap/StaticMethod.h index 73cb66c65..cc8401cad 100644 --- a/wrap/StaticMethod.h +++ b/wrap/StaticMethod.h @@ -44,7 +44,6 @@ protected: virtual std::string wrapper_call(FileWriter& wrapperFile, Str cppClassName, Str matlabUniqueName, const ArgumentList& args, - const ReturnValue& returnVal, const TypeAttributesTable& typeAttributes, const Qualified& instName) const; }; From 6e691b06ffa93fef85f4e93f0ad11f30ccc275b3 Mon Sep 17 00:00:00 2001 From: dellaert Date: Sat, 29 Nov 2014 19:38:51 +0100 Subject: [PATCH 022/126] Private table_ --- wrap/ReturnType.cpp | 2 +- wrap/TypeAttributesTable.cpp | 73 +++++++++++++++++++++++------------- wrap/TypeAttributesTable.h | 31 +++++++++++---- 3 files changed, 70 insertions(+), 36 deletions(-) diff --git a/wrap/ReturnType.cpp b/wrap/ReturnType.cpp index a317a5420..25147e59a 100644 --- a/wrap/ReturnType.cpp +++ b/wrap/ReturnType.cpp @@ -26,7 +26,7 @@ void ReturnType::wrap_result(const string& out, const string& result, if (category == CLASS) { string objCopy, ptrType; ptrType = "Shared" + name; - const bool isVirtual = typeAttributes.at(cppType).isVirtual; + const bool isVirtual = typeAttributes.attributes(cppType).isVirtual; if (isVirtual) { if (isPtr) objCopy = result; diff --git a/wrap/TypeAttributesTable.cpp b/wrap/TypeAttributesTable.cpp index 16055fca1..14c1ab7a4 100644 --- a/wrap/TypeAttributesTable.cpp +++ b/wrap/TypeAttributesTable.cpp @@ -21,42 +21,61 @@ #include "utilities.h" #include +#include +#include +#include // std::ostream_iterator using namespace std; namespace wrap { - /* ************************************************************************* */ - void TypeAttributesTable::addClasses(const vector& classes) { - BOOST_FOREACH(const Class& cls, classes) { - if(!insert(make_pair(cls.qualifiedName("::"), TypeAttributes(cls.isVirtual))).second) - throw DuplicateDefinition("class " + cls.qualifiedName("::")); - } +/* ************************************************************************* */ +const TypeAttributes& TypeAttributesTable::attributes(const string& key) const { + try { + return table_.at(key); + } catch (const out_of_range& oor) { + cerr << "Class::method: key not found: " << oor.what() + << ", methods are:\n"; + using boost::adaptors::map_keys; + ostream_iterator out_it(cerr, "\n"); + boost::copy(table_ | map_keys, out_it); + throw runtime_error("Internal error in wrap"); } +} - /* ************************************************************************* */ - void TypeAttributesTable::addForwardDeclarations(const vector& forwardDecls) { - BOOST_FOREACH(const ForwardDeclaration& fwDec, forwardDecls) { - if(!insert(make_pair(fwDec.name, TypeAttributes(fwDec.isVirtual))).second) - throw DuplicateDefinition("class " + fwDec.name); - } +/* ************************************************************************* */ +void TypeAttributesTable::addClasses(const vector& classes) { + BOOST_FOREACH(const Class& cls, classes) { + if (!table_.insert( + make_pair(cls.qualifiedName("::"), TypeAttributes(cls.isVirtual))).second) + throw DuplicateDefinition("class " + cls.qualifiedName("::")); } +} - /* ************************************************************************* */ - void TypeAttributesTable::checkValidity(const vector& classes) const { - BOOST_FOREACH(const Class& cls, classes) { - // Check that class is virtual if it has a parent - if (!cls.qualifiedParent.empty() && !cls.isVirtual) - throw AttributeError(cls.qualifiedName("::"), - "Has a base class so needs to be declared virtual, change to 'virtual class " - + cls.name + " ...'"); - // Check that parent is virtual as well - Qualified parent = cls.qualifiedParent; - if (!parent.empty() && !at(parent.qualifiedName("::")).isVirtual) - throw AttributeError(parent.qualifiedName("::"), - "Is the base class of " + cls.qualifiedName("::") - + ", so needs to be declared virtual"); - } +/* ************************************************************************* */ +void TypeAttributesTable::addForwardDeclarations( + const vector& forwardDecls) { + BOOST_FOREACH(const ForwardDeclaration& fwDec, forwardDecls) { + if (!table_.insert(make_pair(fwDec.name, TypeAttributes(fwDec.isVirtual))).second) + throw DuplicateDefinition("class " + fwDec.name); } +} + +/* ************************************************************************* */ +void TypeAttributesTable::checkValidity(const vector& classes) const { + BOOST_FOREACH(const Class& cls, classes) { + // Check that class is virtual if it has a parent + if (!cls.qualifiedParent.empty() && !cls.isVirtual) + throw AttributeError(cls.qualifiedName("::"), + "Has a base class so needs to be declared virtual, change to 'virtual class " + + cls.name + " ...'"); + // Check that parent is virtual as well + Qualified parent = cls.qualifiedParent; + if (!parent.empty() && !table_.at(parent.qualifiedName("::")).isVirtual) + throw AttributeError(parent.qualifiedName("::"), + "Is the base class of " + cls.qualifiedName("::") + + ", so needs to be declared virtual"); + } +} } diff --git a/wrap/TypeAttributesTable.h b/wrap/TypeAttributesTable.h index d2a346bfc..9b1c2acbc 100644 --- a/wrap/TypeAttributesTable.h +++ b/wrap/TypeAttributesTable.h @@ -27,9 +27,9 @@ namespace wrap { - // Forward declarations - class Class; - +// Forward declarations +class Class; + /** Attributes about valid classes, both for classes defined in this module and * also those forward-declared from others. At the moment this only contains * whether the class is virtual, which is used to know how to copy the class, @@ -37,18 +37,33 @@ namespace wrap { */ struct TypeAttributes { bool isVirtual; - TypeAttributes() : isVirtual(false) {} - TypeAttributes(bool isVirtual) : isVirtual(isVirtual) {} + TypeAttributes() : + isVirtual(false) { + } + TypeAttributes(bool isVirtual) : + isVirtual(isVirtual) { + } }; /** Map of type names to attributes. */ -class TypeAttributesTable : public std::map { +class TypeAttributesTable { + + std::map table_; + public: - TypeAttributesTable() {} + + /// Constructor + TypeAttributesTable() { + } void addClasses(const std::vector& classes); - void addForwardDeclarations(const std::vector& forwardDecls); + void addForwardDeclarations( + const std::vector& forwardDecls); + /// Access attributes associated with key, informative failure + const TypeAttributes& attributes(const std::string& key) const; + + /// Check that all virtual classes are properly defined void checkValidity(const std::vector& classes) const; }; From fb8283cf1126b535f09e0e177cc17290e37fa6ca Mon Sep 17 00:00:00 2001 From: dellaert Date: Sat, 29 Nov 2014 19:47:45 +0100 Subject: [PATCH 023/126] Fixed message --- wrap/TypeAttributesTable.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/wrap/TypeAttributesTable.cpp b/wrap/TypeAttributesTable.cpp index 14c1ab7a4..a836f2005 100644 --- a/wrap/TypeAttributesTable.cpp +++ b/wrap/TypeAttributesTable.cpp @@ -34,8 +34,8 @@ const TypeAttributes& TypeAttributesTable::attributes(const string& key) const { try { return table_.at(key); } catch (const out_of_range& oor) { - cerr << "Class::method: key not found: " << oor.what() - << ", methods are:\n"; + cerr << "TypeAttributesTable::attributes: key " << key + << " not found. Valid keys are:\n"; using boost::adaptors::map_keys; ostream_iterator out_it(cerr, "\n"); boost::copy(table_ | map_keys, out_it); From e2ab47b610628c4858662e971360a39800511ccb Mon Sep 17 00:00:00 2001 From: dellaert Date: Sat, 29 Nov 2014 20:01:48 +0100 Subject: [PATCH 024/126] Added Vector and Matrix to forward declarations --- wrap/ForwardDeclaration.h | 3 ++- wrap/Module.cpp | 5 +++++ 2 files changed, 7 insertions(+), 1 deletion(-) diff --git a/wrap/ForwardDeclaration.h b/wrap/ForwardDeclaration.h index 5506dd778..5ec022ca4 100644 --- a/wrap/ForwardDeclaration.h +++ b/wrap/ForwardDeclaration.h @@ -27,6 +27,7 @@ namespace wrap { std::string name; bool isVirtual; ForwardDeclaration() : isVirtual(false) {} + ForwardDeclaration(const std::string& s) : name(s), isVirtual(false) {} }; -} \ No newline at end of file +} diff --git a/wrap/Module.cpp b/wrap/Module.cpp index 277845889..912397f21 100644 --- a/wrap/Module.cpp +++ b/wrap/Module.cpp @@ -416,6 +416,11 @@ void Module::parseMarkup(const std::string& data) { // Create type attributes table and check validity typeAttributes.addClasses(expandedClasses); typeAttributes.addForwardDeclarations(forward_declarations); + // add Eigen types as template arguments are also checked ? + vector eigen; + eigen.push_back(ForwardDeclaration("Vector")); + eigen.push_back(ForwardDeclaration("Matrix")); + typeAttributes.addForwardDeclarations(eigen); typeAttributes.checkValidity(expandedClasses); } From 0eaabd700b3354dd837b4b3d295e1a58af993677 Mon Sep 17 00:00:00 2001 From: dellaert Date: Sat, 29 Nov 2014 20:53:38 +0100 Subject: [PATCH 025/126] Refactored emit call --- wrap/Argument.cpp | 19 ++----------------- wrap/Argument.h | 21 ++++----------------- wrap/Function.cpp | 32 +++++++++++++++++++++++++++----- wrap/Function.h | 10 ++++++++++ wrap/GlobalFunction.cpp | 3 ++- wrap/MethodBase.cpp | 5 ++--- 6 files changed, 47 insertions(+), 43 deletions(-) diff --git a/wrap/Argument.cpp b/wrap/Argument.cpp index 4989afb0d..a3c0987d8 100644 --- a/wrap/Argument.cpp +++ b/wrap/Argument.cpp @@ -175,20 +175,9 @@ void ArgumentList::emit_prototype(FileWriter& file, const string& name) const { } file.oss << ")"; } + /* ************************************************************************* */ -void ArgumentList::emit_call(FileWriter& proxyFile, - const ReturnValue& returnVal, const string& wrapperName, int id, - bool staticMethod) const { - returnVal.emit_matlab(proxyFile); - proxyFile.oss << wrapperName << "(" << id; - if (!staticMethod) - proxyFile.oss << ", this"; - proxyFile.oss << ", varargin{:});\n"; -} -/* ************************************************************************* */ -void ArgumentList::emit_conditional_call(FileWriter& proxyFile, - const ReturnValue& returnVal, const string& wrapperName, int id, - bool staticMethod) const { +void ArgumentList::proxy_check_arguments(FileWriter& proxyFile) const { // Check nr of arguments proxyFile.oss << "if length(varargin) == " << size(); if (size() > 0) @@ -203,10 +192,6 @@ void ArgumentList::emit_conditional_call(FileWriter& proxyFile, first = false; } proxyFile.oss << "\n"; - - // output call to C++ wrapper - proxyFile.oss << " "; - emit_call(proxyFile, returnVal, wrapperName, id, staticMethod); } /* ************************************************************************* */ diff --git a/wrap/Argument.h b/wrap/Argument.h index 3d8d7288f..f207e0766 100644 --- a/wrap/Argument.h +++ b/wrap/Argument.h @@ -88,26 +88,12 @@ struct ArgumentList: public std::vector { void emit_prototype(FileWriter& file, const std::string& name) const; /** - * emit emit MATLAB call to proxy + * emit checking arguments to MATLAB proxy * @param proxyFile output stream - * @param returnVal the return value - * @param wrapperName of method or function - * @param staticMethod flag to emit "this" in call */ - void emit_call(FileWriter& proxyFile, const ReturnValue& returnVal, - const std::string& wrapperName, int id, bool staticMethod = false) const; - - /** - * emit conditional MATLAB call to proxy (checking arguments first) - * @param proxyFile output stream - * @param returnVal the return value - * @param wrapperName of method or function - * @param staticMethod flag to emit "this" in call - */ - void emit_conditional_call(FileWriter& proxyFile, - const ReturnValue& returnVal, const std::string& wrapperName, int id, - bool staticMethod = false) const; + void proxy_check_arguments(FileWriter& proxyFile) const; + /// Output stream operator friend std::ostream& operator<<(std::ostream& os, const ArgumentList& argList) { os << "("; @@ -120,6 +106,7 @@ struct ArgumentList: public std::vector { return os; } + }; } // \namespace wrap diff --git a/wrap/Function.cpp b/wrap/Function.cpp index 6faa70fb9..29165c64b 100644 --- a/wrap/Function.cpp +++ b/wrap/Function.cpp @@ -29,12 +29,11 @@ using namespace std; using namespace wrap; /* ************************************************************************* */ -bool Function::initializeOrCheck(const std::string& name, - const Qualified& instName, bool verbose) { +bool Function::initializeOrCheck(const string& name, const Qualified& instName, + bool verbose) { if (name.empty()) - throw std::runtime_error( - "Function::initializeOrCheck called with empty name"); + throw runtime_error("Function::initializeOrCheck called with empty name"); // Check if this overload is give to the correct method if (name_.empty()) { @@ -44,7 +43,7 @@ bool Function::initializeOrCheck(const std::string& name, return true; } else { if (name_ != name || templateArgValue_ != instName || verbose_ != verbose) - throw std::runtime_error( + throw runtime_error( "Function::initializeOrCheck called with different arguments: with name " + name + " instead of expected " + name_ + ", or with template argument " + instName.qualifiedName(":") @@ -55,3 +54,26 @@ bool Function::initializeOrCheck(const std::string& name, } /* ************************************************************************* */ +void Function::emit_call(FileWriter& proxyFile, const ReturnValue& returnVal, + const string& wrapperName, int id, bool staticMethod) const { + returnVal.emit_matlab(proxyFile); + proxyFile.oss << wrapperName << "(" << id; + if (!staticMethod) + proxyFile.oss << ", this"; + proxyFile.oss << ", varargin{:});\n"; +} + +/* ************************************************************************* */ +void Function::emit_conditional_call(FileWriter& proxyFile, + const ReturnValue& returnVal, const ArgumentList& args, + const string& wrapperName, int id, bool staticMethod) const { + + // Check all arguments + args.proxy_check_arguments(proxyFile); + + // output call to C++ wrapper + proxyFile.oss << " "; + emit_call(proxyFile, returnVal, wrapperName, id, staticMethod); +} + +/* ************************************************************************* */ diff --git a/wrap/Function.h b/wrap/Function.h index 49a26bd8d..388e6568b 100644 --- a/wrap/Function.h +++ b/wrap/Function.h @@ -50,6 +50,16 @@ public: else return name_ + templateArgValue_.name; } + + /// Emit function call to MATLAB (no argument checking) + void emit_call(FileWriter& proxyFile, const ReturnValue& returnVal, + const std::string& wrapperName, int id, bool staticMethod) const; + + /// Emit checking arguments and function call to MATLAB + void emit_conditional_call(FileWriter& proxyFile, + const ReturnValue& returnVal, const ArgumentList& args, + const std::string& wrapperName, int id, bool staticMethod) const; + }; } // \namespace wrap diff --git a/wrap/GlobalFunction.cpp b/wrap/GlobalFunction.cpp index e843481a1..18f5c5f6c 100644 --- a/wrap/GlobalFunction.cpp +++ b/wrap/GlobalFunction.cpp @@ -80,7 +80,8 @@ void GlobalFunction::generateSingleFunction(const string& toolboxPath, // Output proxy matlab code mfunctionFile.oss << " " << (i == 0 ? "" : "else"); - args.emit_conditional_call(mfunctionFile, returnVal, wrapperName, id, true); // true omits "this" + emit_conditional_call(mfunctionFile, returnVal, args, wrapperName, id, + true); // true omits "this" // Output C++ wrapper code diff --git a/wrap/MethodBase.cpp b/wrap/MethodBase.cpp index a63b95b90..124963d9a 100644 --- a/wrap/MethodBase.cpp +++ b/wrap/MethodBase.cpp @@ -55,8 +55,7 @@ void MethodBase::proxy_wrapper_fragments(FileWriter& proxyFile, // TODO: document why is it OK to not check arguments in this case proxyFile.oss << " "; const int id = (int) functionNames.size(); - argumentList(0).emit_call(proxyFile, returnValue(0), wrapperName, id, - isStatic()); + emit_call(proxyFile, returnValue(0), wrapperName, id, isStatic()); // Output C++ wrapper code const string wrapFunctionName = wrapper_fragment(wrapperFile, cppClassName, @@ -71,7 +70,7 @@ void MethodBase::proxy_wrapper_fragments(FileWriter& proxyFile, // Output proxy matlab code proxyFile.oss << " " << (i == 0 ? "" : "else"); const int id = (int) functionNames.size(); - argumentList(i).emit_conditional_call(proxyFile, returnValue(i), + emit_conditional_call(proxyFile, returnValue(i), argumentList(i), wrapperName, id, isStatic()); // Output C++ wrapper code From 0261c590638682776b06be02e163e2740244a0b6 Mon Sep 17 00:00:00 2001 From: dellaert Date: Sat, 29 Nov 2014 20:59:38 +0100 Subject: [PATCH 026/126] static property is known by function! Makes so much more sense... --- wrap/Function.cpp | 8 ++++---- wrap/Function.h | 9 +++++++-- wrap/GlobalFunction.cpp | 3 +-- wrap/MethodBase.cpp | 4 ++-- wrap/MethodBase.h | 2 -- wrap/StaticMethod.h | 4 ---- 6 files changed, 14 insertions(+), 16 deletions(-) diff --git a/wrap/Function.cpp b/wrap/Function.cpp index 29165c64b..b939c3cee 100644 --- a/wrap/Function.cpp +++ b/wrap/Function.cpp @@ -55,10 +55,10 @@ bool Function::initializeOrCheck(const string& name, const Qualified& instName, /* ************************************************************************* */ void Function::emit_call(FileWriter& proxyFile, const ReturnValue& returnVal, - const string& wrapperName, int id, bool staticMethod) const { + const string& wrapperName, int id) const { returnVal.emit_matlab(proxyFile); proxyFile.oss << wrapperName << "(" << id; - if (!staticMethod) + if (!isStatic()) proxyFile.oss << ", this"; proxyFile.oss << ", varargin{:});\n"; } @@ -66,14 +66,14 @@ void Function::emit_call(FileWriter& proxyFile, const ReturnValue& returnVal, /* ************************************************************************* */ void Function::emit_conditional_call(FileWriter& proxyFile, const ReturnValue& returnVal, const ArgumentList& args, - const string& wrapperName, int id, bool staticMethod) const { + const string& wrapperName, int id) const { // Check all arguments args.proxy_check_arguments(proxyFile); // output call to C++ wrapper proxyFile.oss << " "; - emit_call(proxyFile, returnVal, wrapperName, id, staticMethod); + emit_call(proxyFile, returnVal, wrapperName, id); } /* ************************************************************************* */ diff --git a/wrap/Function.h b/wrap/Function.h index 388e6568b..249cd42a7 100644 --- a/wrap/Function.h +++ b/wrap/Function.h @@ -44,6 +44,11 @@ public: return name_; } + /// Only Methods are non-static + virtual bool isStatic() const { + return true; + } + std::string matlabName() const { if (templateArgValue_.empty()) return name_; @@ -53,12 +58,12 @@ public: /// Emit function call to MATLAB (no argument checking) void emit_call(FileWriter& proxyFile, const ReturnValue& returnVal, - const std::string& wrapperName, int id, bool staticMethod) const; + const std::string& wrapperName, int id) const; /// Emit checking arguments and function call to MATLAB void emit_conditional_call(FileWriter& proxyFile, const ReturnValue& returnVal, const ArgumentList& args, - const std::string& wrapperName, int id, bool staticMethod) const; + const std::string& wrapperName, int id) const; }; diff --git a/wrap/GlobalFunction.cpp b/wrap/GlobalFunction.cpp index 18f5c5f6c..dfeb46dce 100644 --- a/wrap/GlobalFunction.cpp +++ b/wrap/GlobalFunction.cpp @@ -80,8 +80,7 @@ void GlobalFunction::generateSingleFunction(const string& toolboxPath, // Output proxy matlab code mfunctionFile.oss << " " << (i == 0 ? "" : "else"); - emit_conditional_call(mfunctionFile, returnVal, args, wrapperName, id, - true); // true omits "this" + emit_conditional_call(mfunctionFile, returnVal, args, wrapperName, id); // Output C++ wrapper code diff --git a/wrap/MethodBase.cpp b/wrap/MethodBase.cpp index 124963d9a..643d8ceec 100644 --- a/wrap/MethodBase.cpp +++ b/wrap/MethodBase.cpp @@ -55,7 +55,7 @@ void MethodBase::proxy_wrapper_fragments(FileWriter& proxyFile, // TODO: document why is it OK to not check arguments in this case proxyFile.oss << " "; const int id = (int) functionNames.size(); - emit_call(proxyFile, returnValue(0), wrapperName, id, isStatic()); + emit_call(proxyFile, returnValue(0), wrapperName, id); // Output C++ wrapper code const string wrapFunctionName = wrapper_fragment(wrapperFile, cppClassName, @@ -71,7 +71,7 @@ void MethodBase::proxy_wrapper_fragments(FileWriter& proxyFile, proxyFile.oss << " " << (i == 0 ? "" : "else"); const int id = (int) functionNames.size(); emit_conditional_call(proxyFile, returnValue(i), argumentList(i), - wrapperName, id, isStatic()); + wrapperName, id); // Output C++ wrapper code const string wrapFunctionName = wrapper_fragment(wrapperFile, diff --git a/wrap/MethodBase.h b/wrap/MethodBase.h index da50b8124..0aabe819d 100644 --- a/wrap/MethodBase.h +++ b/wrap/MethodBase.h @@ -28,8 +28,6 @@ struct MethodBase: public FullyOverloadedFunction { typedef const std::string& Str; - virtual bool isStatic() const = 0; - // emit a list of comments, one for each overload void comment_fragment(FileWriter& proxyFile) const { SignatureOverloads::comment_fragment(proxyFile, matlabName()); diff --git a/wrap/StaticMethod.h b/wrap/StaticMethod.h index cc8401cad..c3bf526dd 100644 --- a/wrap/StaticMethod.h +++ b/wrap/StaticMethod.h @@ -28,10 +28,6 @@ struct StaticMethod: public MethodBase { typedef const std::string& Str; - virtual bool isStatic() const { - return true; - } - friend std::ostream& operator<<(std::ostream& os, const StaticMethod& m) { for (size_t i = 0; i < m.nrOverloads(); i++) os << "static " << m.returnVals_[i] << " " << m.name_ << m.argLists_[i]; From 370f2c6763d640090a22589a66b54886d2f7d3f0 Mon Sep 17 00:00:00 2001 From: dellaert Date: Sat, 29 Nov 2014 21:11:13 +0100 Subject: [PATCH 027/126] Isolated argument check --- wrap/Argument.cpp | 15 +++++++++++---- wrap/Argument.h | 9 +++++++-- wrap/Function.cpp | 2 +- 3 files changed, 19 insertions(+), 7 deletions(-) diff --git a/wrap/Argument.cpp b/wrap/Argument.cpp index a3c0987d8..d49e00d82 100644 --- a/wrap/Argument.cpp +++ b/wrap/Argument.cpp @@ -36,7 +36,8 @@ Argument Argument::expandTemplate(const TemplateSubstitution& ts) const { } /* ************************************************************************* */ -ArgumentList ArgumentList::expandTemplate(const TemplateSubstitution& ts) const { +ArgumentList ArgumentList::expandTemplate( + const TemplateSubstitution& ts) const { ArgumentList instArgList; BOOST_FOREACH(const Argument& arg, *this) { Argument instArg = arg.expandTemplate(ts); @@ -97,6 +98,12 @@ void Argument::matlab_unwrap(FileWriter& file, const string& matlabName) const { file.oss << ");" << endl; } +/* ************************************************************************* */ +void Argument::proxy_check(FileWriter& proxyFile, size_t sequenceNr) const { + proxyFile.oss << "isa(varargin{" << sequenceNr << "},'" << matlabClass(".") + << "')"; +} + /* ************************************************************************* */ string ArgumentList::types() const { string str; @@ -177,7 +184,7 @@ void ArgumentList::emit_prototype(FileWriter& file, const string& name) const { } /* ************************************************************************* */ -void ArgumentList::proxy_check_arguments(FileWriter& proxyFile) const { +void ArgumentList::proxy_check(FileWriter& proxyFile) const { // Check nr of arguments proxyFile.oss << "if length(varargin) == " << size(); if (size() > 0) @@ -187,11 +194,11 @@ void ArgumentList::proxy_check_arguments(FileWriter& proxyFile) const { for (size_t i = 0; i < size(); i++) { if (!first) proxyFile.oss << " && "; - proxyFile.oss << "isa(varargin{" << i + 1 << "},'" - << (*this)[i].matlabClass(".") << "')"; + (*this)[i].proxy_check(proxyFile, i + 1); first = false; } proxyFile.oss << "\n"; } + /* ************************************************************************* */ diff --git a/wrap/Argument.h b/wrap/Argument.h index f207e0766..b440e3941 100644 --- a/wrap/Argument.h +++ b/wrap/Argument.h @@ -46,6 +46,12 @@ struct Argument { /// MATLAB code generation, MATLAB to C++ void matlab_unwrap(FileWriter& file, const std::string& matlabName) const; + /** + * emit checking argument to MATLAB proxy + * @param proxyFile output stream + */ + void proxy_check(FileWriter& proxyFile, size_t sequenceNr) const; + friend std::ostream& operator<<(std::ostream& os, const Argument& arg) { os << (arg.is_const ? "const " : "") << arg.type << (arg.is_ptr ? "*" : "") << (arg.is_ref ? "&" : ""); @@ -91,7 +97,7 @@ struct ArgumentList: public std::vector { * emit checking arguments to MATLAB proxy * @param proxyFile output stream */ - void proxy_check_arguments(FileWriter& proxyFile) const; + void proxy_check(FileWriter& proxyFile) const; /// Output stream operator friend std::ostream& operator<<(std::ostream& os, @@ -106,7 +112,6 @@ struct ArgumentList: public std::vector { return os; } - }; } // \namespace wrap diff --git a/wrap/Function.cpp b/wrap/Function.cpp index b939c3cee..d045d2915 100644 --- a/wrap/Function.cpp +++ b/wrap/Function.cpp @@ -69,7 +69,7 @@ void Function::emit_conditional_call(FileWriter& proxyFile, const string& wrapperName, int id) const { // Check all arguments - args.proxy_check_arguments(proxyFile); + args.proxy_check(proxyFile); // output call to C++ wrapper proxyFile.oss << " "; From 8d9e108acca3f461a6b50abee3132e8cc1174125 Mon Sep 17 00:00:00 2001 From: dellaert Date: Sat, 29 Nov 2014 21:43:48 +0100 Subject: [PATCH 028/126] Check Vector by checking size --- wrap/Argument.cpp | 11 +- wrap/Argument.h | 2 +- .../tests/expected-python/geometry_python.cpp | 1 + wrap/tests/expected2/+gtsam/Point2.m | 19 +- wrap/tests/expected2/+gtsam/Point3.m | 12 +- wrap/tests/expected2/MyBase.m | 6 +- wrap/tests/expected2/MyFactorPosePoint2.m | 6 +- wrap/tests/expected2/MyTemplatePoint2.m | 32 +- wrap/tests/expected2/MyTemplatePoint3.m | 32 +- wrap/tests/expected2/Test.m | 52 ++-- wrap/tests/expected2/aGlobalFunction.m | 2 +- wrap/tests/expected2/geometry_wrapper.cpp | 285 +++++++++--------- .../expected2/overloadedGlobalFunction.m | 4 +- wrap/tests/geometry.h | 1 + wrap/tests/testWrap.cpp | 2 +- 15 files changed, 248 insertions(+), 219 deletions(-) diff --git a/wrap/Argument.cpp b/wrap/Argument.cpp index d49e00d82..2350a77d7 100644 --- a/wrap/Argument.cpp +++ b/wrap/Argument.cpp @@ -20,6 +20,7 @@ #include #include +#include #include #include @@ -99,9 +100,10 @@ void Argument::matlab_unwrap(FileWriter& file, const string& matlabName) const { } /* ************************************************************************* */ -void Argument::proxy_check(FileWriter& proxyFile, size_t sequenceNr) const { - proxyFile.oss << "isa(varargin{" << sequenceNr << "},'" << matlabClass(".") - << "')"; +void Argument::proxy_check(FileWriter& proxyFile, const string& s) const { + proxyFile.oss << "isa(" << s << ",'" << matlabClass(".") << "')"; + if (type.name == "Vector") + proxyFile.oss << " && size(" << s << ",2)==1"; } /* ************************************************************************* */ @@ -194,7 +196,8 @@ void ArgumentList::proxy_check(FileWriter& proxyFile) const { for (size_t i = 0; i < size(); i++) { if (!first) proxyFile.oss << " && "; - (*this)[i].proxy_check(proxyFile, i + 1); + string s = "varargin{" + boost::lexical_cast(i + 1) + "}"; + (*this)[i].proxy_check(proxyFile, s); first = false; } proxyFile.oss << "\n"; diff --git a/wrap/Argument.h b/wrap/Argument.h index b440e3941..200269cc3 100644 --- a/wrap/Argument.h +++ b/wrap/Argument.h @@ -50,7 +50,7 @@ struct Argument { * emit checking argument to MATLAB proxy * @param proxyFile output stream */ - void proxy_check(FileWriter& proxyFile, size_t sequenceNr) const; + void proxy_check(FileWriter& proxyFile, const std::string& s) const; friend std::ostream& operator<<(std::ostream& os, const Argument& arg) { os << (arg.is_const ? "const " : "") << arg.type << (arg.is_ptr ? "*" : "") diff --git a/wrap/tests/expected-python/geometry_python.cpp b/wrap/tests/expected-python/geometry_python.cpp index b28e69709..ca8698397 100644 --- a/wrap/tests/expected-python/geometry_python.cpp +++ b/wrap/tests/expected-python/geometry_python.cpp @@ -8,6 +8,7 @@ class_("Point2") .def("argChar", &Point2::argChar); .def("argUChar", &Point2::argUChar); .def("dim", &Point2::dim); + .def("eigenArguments", &Point2::eigenArguments); .def("returnChar", &Point2::returnChar); .def("vectorConfusion", &Point2::vectorConfusion); .def("x", &Point2::x); diff --git a/wrap/tests/expected2/+gtsam/Point2.m b/wrap/tests/expected2/+gtsam/Point2.m index 308b35d9a..05ca8b9a0 100644 --- a/wrap/tests/expected2/+gtsam/Point2.m +++ b/wrap/tests/expected2/+gtsam/Point2.m @@ -9,6 +9,7 @@ %argChar(char a) : returns void %argUChar(unsigned char a) : returns void %dim() : returns int +%eigenArguments(Vector v, Matrix m) : returns void %returnChar() : returns char %vectorConfusion() : returns VectorNotEigen %x() : returns double @@ -59,28 +60,38 @@ classdef Point2 < handle varargout{1} = geometry_wrapper(6, this, varargin{:}); end + function varargout = eigenArguments(this, varargin) + % EIGENARGUMENTS usage: eigenArguments(Vector v, Matrix m) : returns void + % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html + if length(varargin) == 2 && isa(varargin{1},'double') && size(varargin{1},2)==1 && isa(varargin{2},'double') + geometry_wrapper(7, this, varargin{:}); + else + error('Arguments do not match any overload of function gtsam.Point2.eigenArguments'); + end + end + function varargout = returnChar(this, varargin) % RETURNCHAR usage: returnChar() : returns char % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html - varargout{1} = geometry_wrapper(7, this, varargin{:}); + varargout{1} = geometry_wrapper(8, this, varargin{:}); end function varargout = vectorConfusion(this, varargin) % VECTORCONFUSION usage: vectorConfusion() : returns VectorNotEigen % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html - varargout{1} = geometry_wrapper(8, this, varargin{:}); + varargout{1} = geometry_wrapper(9, this, varargin{:}); end function varargout = x(this, varargin) % X usage: x() : returns double % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html - varargout{1} = geometry_wrapper(9, this, varargin{:}); + varargout{1} = geometry_wrapper(10, this, varargin{:}); end function varargout = y(this, varargin) % Y usage: y() : returns double % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html - varargout{1} = geometry_wrapper(10, this, varargin{:}); + varargout{1} = geometry_wrapper(11, this, varargin{:}); end end diff --git a/wrap/tests/expected2/+gtsam/Point3.m b/wrap/tests/expected2/+gtsam/Point3.m index 3ef336ff1..acdc7239d 100644 --- a/wrap/tests/expected2/+gtsam/Point3.m +++ b/wrap/tests/expected2/+gtsam/Point3.m @@ -19,9 +19,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(11, my_ptr); + geometry_wrapper(12, my_ptr); elseif nargin == 3 && isa(varargin{1},'double') && isa(varargin{2},'double') && isa(varargin{3},'double') - my_ptr = geometry_wrapper(12, varargin{1}, varargin{2}, varargin{3}); + my_ptr = geometry_wrapper(13, varargin{1}, varargin{2}, varargin{3}); else error('Arguments do not match any overload of gtsam.Point3 constructor'); end @@ -29,7 +29,7 @@ classdef Point3 < handle end function delete(obj) - geometry_wrapper(13, obj.ptr_gtsamPoint3); + geometry_wrapper(14, obj.ptr_gtsamPoint3); end function display(obj), obj.print(''); end @@ -39,7 +39,7 @@ classdef Point3 < handle function varargout = norm(this, varargin) % NORM usage: norm() : returns double % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html - varargout{1} = geometry_wrapper(14, this, varargin{:}); + varargout{1} = geometry_wrapper(15, this, varargin{:}); end end @@ -48,13 +48,13 @@ classdef Point3 < handle function varargout = StaticFunctionRet(varargin) % STATICFUNCTIONRET usage: StaticFunctionRet(double z) : returns gtsam::Point3 % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html - varargout{1} = geometry_wrapper(15, varargin{:}); + varargout{1} = geometry_wrapper(16, varargin{:}); end function varargout = StaticFunction(varargin) % STATICFUNCTION usage: staticFunction() : returns double % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html - varargout{1} = geometry_wrapper(16, varargin{:}); + varargout{1} = geometry_wrapper(17, varargin{:}); end end diff --git a/wrap/tests/expected2/MyBase.m b/wrap/tests/expected2/MyBase.m index d7bfe7e81..98eab005b 100644 --- a/wrap/tests/expected2/MyBase.m +++ b/wrap/tests/expected2/MyBase.m @@ -11,9 +11,9 @@ classdef MyBase < handle if nargin == 2 my_ptr = varargin{2}; else - my_ptr = geometry_wrapper(41, varargin{2}); + my_ptr = geometry_wrapper(42, varargin{2}); end - geometry_wrapper(40, my_ptr); + geometry_wrapper(41, 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(42, obj.ptr_MyBase); + geometry_wrapper(43, obj.ptr_MyBase); end function display(obj), obj.print(''); end diff --git a/wrap/tests/expected2/MyFactorPosePoint2.m b/wrap/tests/expected2/MyFactorPosePoint2.m index e55386cc0..430206232 100644 --- a/wrap/tests/expected2/MyFactorPosePoint2.m +++ b/wrap/tests/expected2/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(73, my_ptr); + geometry_wrapper(74, 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(74, varargin{1}, varargin{2}, varargin{3}, varargin{4}); + my_ptr = geometry_wrapper(75, 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(75, obj.ptr_MyFactorPosePoint2); + geometry_wrapper(76, obj.ptr_MyFactorPosePoint2); end function display(obj), obj.print(''); end diff --git a/wrap/tests/expected2/MyTemplatePoint2.m b/wrap/tests/expected2/MyTemplatePoint2.m index 9df4d2d1a..ace466ed7 100644 --- a/wrap/tests/expected2/MyTemplatePoint2.m +++ b/wrap/tests/expected2/MyTemplatePoint2.m @@ -27,11 +27,11 @@ classdef MyTemplatePoint2 < MyBase if nargin == 2 my_ptr = varargin{2}; else - my_ptr = geometry_wrapper(44, varargin{2}); + my_ptr = geometry_wrapper(45, varargin{2}); end - base_ptr = geometry_wrapper(43, my_ptr); + base_ptr = geometry_wrapper(44, my_ptr); elseif nargin == 0 - [ my_ptr, base_ptr ] = geometry_wrapper(45); + [ my_ptr, base_ptr ] = geometry_wrapper(46); else error('Arguments do not match any overload of MyTemplatePoint2 constructor'); end @@ -40,7 +40,7 @@ classdef MyTemplatePoint2 < MyBase end function delete(obj) - geometry_wrapper(46, obj.ptr_MyTemplatePoint2); + geometry_wrapper(47, obj.ptr_MyTemplatePoint2); end function display(obj), obj.print(''); end @@ -51,7 +51,7 @@ classdef MyTemplatePoint2 < MyBase % ACCEPT_T usage: accept_T(Point2 value) : returns void % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html if length(varargin) == 1 && isa(varargin{1},'gtsam.Point2') - geometry_wrapper(47, this, varargin{:}); + geometry_wrapper(48, this, varargin{:}); else error('Arguments do not match any overload of function MyTemplatePoint2.accept_T'); end @@ -61,7 +61,7 @@ classdef MyTemplatePoint2 < MyBase % ACCEPT_TPTR usage: accept_Tptr(Point2 value) : returns void % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html if length(varargin) == 1 && isa(varargin{1},'gtsam.Point2') - geometry_wrapper(48, this, varargin{:}); + geometry_wrapper(49, this, varargin{:}); else error('Arguments do not match any overload of function MyTemplatePoint2.accept_Tptr'); end @@ -70,20 +70,20 @@ classdef MyTemplatePoint2 < MyBase function varargout = create_MixedPtrs(this, varargin) % CREATE_MIXEDPTRS usage: create_MixedPtrs() : returns pair< gtsam::Point2, gtsam::Point2 > % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html - [ varargout{1} varargout{2} ] = geometry_wrapper(49, this, varargin{:}); + [ varargout{1} varargout{2} ] = geometry_wrapper(50, this, varargin{:}); end function varargout = create_ptrs(this, varargin) % CREATE_PTRS usage: create_ptrs() : returns pair< gtsam::Point2, gtsam::Point2 > % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html - [ varargout{1} varargout{2} ] = geometry_wrapper(50, this, varargin{:}); + [ varargout{1} varargout{2} ] = geometry_wrapper(51, this, varargin{:}); end function varargout = return_T(this, varargin) % RETURN_T usage: return_T(Point2 value) : returns gtsam::Point2 % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html if length(varargin) == 1 && isa(varargin{1},'gtsam.Point2') - varargout{1} = geometry_wrapper(51, this, varargin{:}); + varargout{1} = geometry_wrapper(52, this, varargin{:}); else error('Arguments do not match any overload of function MyTemplatePoint2.return_T'); end @@ -93,7 +93,7 @@ classdef MyTemplatePoint2 < MyBase % RETURN_TPTR usage: return_Tptr(Point2 value) : returns gtsam::Point2 % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html if length(varargin) == 1 && isa(varargin{1},'gtsam.Point2') - varargout{1} = geometry_wrapper(52, this, varargin{:}); + varargout{1} = geometry_wrapper(53, this, varargin{:}); else error('Arguments do not match any overload of function MyTemplatePoint2.return_Tptr'); end @@ -103,7 +103,7 @@ classdef MyTemplatePoint2 < MyBase % RETURN_PTRS usage: return_ptrs(Point2 p1, Point2 p2) : returns pair< gtsam::Point2, gtsam::Point2 > % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html if length(varargin) == 2 && isa(varargin{1},'gtsam.Point2') && isa(varargin{2},'gtsam.Point2') - [ varargout{1} varargout{2} ] = geometry_wrapper(53, this, varargin{:}); + [ varargout{1} varargout{2} ] = geometry_wrapper(54, this, varargin{:}); else error('Arguments do not match any overload of function MyTemplatePoint2.return_ptrs'); end @@ -113,7 +113,7 @@ classdef MyTemplatePoint2 < MyBase % TEMPLATEDMETHODMATRIX usage: templatedMethodMatrix(Matrix t) : returns void % 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') - geometry_wrapper(54, this, varargin{:}); + geometry_wrapper(55, this, varargin{:}); else error('Arguments do not match any overload of function MyTemplatePoint2.templatedMethod'); end @@ -123,7 +123,7 @@ classdef MyTemplatePoint2 < MyBase % TEMPLATEDMETHODPOINT2 usage: templatedMethodPoint2(Point2 t) : returns void % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html if length(varargin) == 1 && isa(varargin{1},'gtsam.Point2') - geometry_wrapper(55, this, varargin{:}); + geometry_wrapper(56, this, varargin{:}); else error('Arguments do not match any overload of function MyTemplatePoint2.templatedMethod'); end @@ -133,7 +133,7 @@ classdef MyTemplatePoint2 < MyBase % TEMPLATEDMETHODPOINT3 usage: templatedMethodPoint3(Point3 t) : returns void % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html if length(varargin) == 1 && isa(varargin{1},'gtsam.Point3') - geometry_wrapper(56, this, varargin{:}); + geometry_wrapper(57, this, varargin{:}); else error('Arguments do not match any overload of function MyTemplatePoint2.templatedMethod'); end @@ -142,8 +142,8 @@ classdef MyTemplatePoint2 < MyBase function varargout = templatedMethodVector(this, varargin) % TEMPLATEDMETHODVECTOR usage: templatedMethodVector(Vector t) : returns void % 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') - geometry_wrapper(57, this, varargin{:}); + if length(varargin) == 1 && isa(varargin{1},'double') && size(varargin{1},2)==1 + geometry_wrapper(58, this, varargin{:}); else error('Arguments do not match any overload of function MyTemplatePoint2.templatedMethod'); end diff --git a/wrap/tests/expected2/MyTemplatePoint3.m b/wrap/tests/expected2/MyTemplatePoint3.m index 274768d3a..bd0966ef1 100644 --- a/wrap/tests/expected2/MyTemplatePoint3.m +++ b/wrap/tests/expected2/MyTemplatePoint3.m @@ -27,11 +27,11 @@ classdef MyTemplatePoint3 < MyBase if nargin == 2 my_ptr = varargin{2}; else - my_ptr = geometry_wrapper(59, varargin{2}); + my_ptr = geometry_wrapper(60, varargin{2}); end - base_ptr = geometry_wrapper(58, my_ptr); + base_ptr = geometry_wrapper(59, my_ptr); elseif nargin == 0 - [ my_ptr, base_ptr ] = geometry_wrapper(60); + [ my_ptr, base_ptr ] = geometry_wrapper(61); else error('Arguments do not match any overload of MyTemplatePoint3 constructor'); end @@ -40,7 +40,7 @@ classdef MyTemplatePoint3 < MyBase end function delete(obj) - geometry_wrapper(61, obj.ptr_MyTemplatePoint3); + geometry_wrapper(62, obj.ptr_MyTemplatePoint3); end function display(obj), obj.print(''); end @@ -51,7 +51,7 @@ classdef MyTemplatePoint3 < MyBase % ACCEPT_T usage: accept_T(Point3 value) : returns void % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html if length(varargin) == 1 && isa(varargin{1},'gtsam.Point3') - geometry_wrapper(62, this, varargin{:}); + geometry_wrapper(63, this, varargin{:}); else error('Arguments do not match any overload of function MyTemplatePoint3.accept_T'); end @@ -61,7 +61,7 @@ classdef MyTemplatePoint3 < MyBase % ACCEPT_TPTR usage: accept_Tptr(Point3 value) : returns void % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html if length(varargin) == 1 && isa(varargin{1},'gtsam.Point3') - geometry_wrapper(63, this, varargin{:}); + geometry_wrapper(64, this, varargin{:}); else error('Arguments do not match any overload of function MyTemplatePoint3.accept_Tptr'); end @@ -70,20 +70,20 @@ classdef MyTemplatePoint3 < MyBase function varargout = create_MixedPtrs(this, varargin) % CREATE_MIXEDPTRS usage: create_MixedPtrs() : returns pair< gtsam::Point3, gtsam::Point3 > % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html - [ varargout{1} varargout{2} ] = geometry_wrapper(64, this, varargin{:}); + [ varargout{1} varargout{2} ] = geometry_wrapper(65, this, varargin{:}); end function varargout = create_ptrs(this, varargin) % CREATE_PTRS usage: create_ptrs() : returns pair< gtsam::Point3, gtsam::Point3 > % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html - [ varargout{1} varargout{2} ] = geometry_wrapper(65, this, varargin{:}); + [ varargout{1} varargout{2} ] = geometry_wrapper(66, this, varargin{:}); end function varargout = return_T(this, varargin) % RETURN_T usage: return_T(Point3 value) : returns gtsam::Point3 % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html if length(varargin) == 1 && isa(varargin{1},'gtsam.Point3') - varargout{1} = geometry_wrapper(66, this, varargin{:}); + varargout{1} = geometry_wrapper(67, this, varargin{:}); else error('Arguments do not match any overload of function MyTemplatePoint3.return_T'); end @@ -93,7 +93,7 @@ classdef MyTemplatePoint3 < MyBase % RETURN_TPTR usage: return_Tptr(Point3 value) : returns gtsam::Point3 % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html if length(varargin) == 1 && isa(varargin{1},'gtsam.Point3') - varargout{1} = geometry_wrapper(67, this, varargin{:}); + varargout{1} = geometry_wrapper(68, this, varargin{:}); else error('Arguments do not match any overload of function MyTemplatePoint3.return_Tptr'); end @@ -103,7 +103,7 @@ classdef MyTemplatePoint3 < MyBase % RETURN_PTRS usage: return_ptrs(Point3 p1, Point3 p2) : returns pair< gtsam::Point3, gtsam::Point3 > % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html if length(varargin) == 2 && isa(varargin{1},'gtsam.Point3') && isa(varargin{2},'gtsam.Point3') - [ varargout{1} varargout{2} ] = geometry_wrapper(68, this, varargin{:}); + [ varargout{1} varargout{2} ] = geometry_wrapper(69, this, varargin{:}); else error('Arguments do not match any overload of function MyTemplatePoint3.return_ptrs'); end @@ -113,7 +113,7 @@ classdef MyTemplatePoint3 < MyBase % TEMPLATEDMETHODMATRIX usage: templatedMethodMatrix(Matrix t) : returns void % 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') - geometry_wrapper(69, this, varargin{:}); + geometry_wrapper(70, this, varargin{:}); else error('Arguments do not match any overload of function MyTemplatePoint3.templatedMethod'); end @@ -123,7 +123,7 @@ classdef MyTemplatePoint3 < MyBase % TEMPLATEDMETHODPOINT2 usage: templatedMethodPoint2(Point2 t) : returns void % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html if length(varargin) == 1 && isa(varargin{1},'gtsam.Point2') - geometry_wrapper(70, this, varargin{:}); + geometry_wrapper(71, this, varargin{:}); else error('Arguments do not match any overload of function MyTemplatePoint3.templatedMethod'); end @@ -133,7 +133,7 @@ classdef MyTemplatePoint3 < MyBase % TEMPLATEDMETHODPOINT3 usage: templatedMethodPoint3(Point3 t) : returns void % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html if length(varargin) == 1 && isa(varargin{1},'gtsam.Point3') - geometry_wrapper(71, this, varargin{:}); + geometry_wrapper(72, this, varargin{:}); else error('Arguments do not match any overload of function MyTemplatePoint3.templatedMethod'); end @@ -142,8 +142,8 @@ classdef MyTemplatePoint3 < MyBase function varargout = templatedMethodVector(this, varargin) % TEMPLATEDMETHODVECTOR usage: templatedMethodVector(Vector t) : returns void % 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') - geometry_wrapper(72, this, varargin{:}); + if length(varargin) == 1 && isa(varargin{1},'double') && size(varargin{1},2)==1 + geometry_wrapper(73, this, varargin{:}); else error('Arguments do not match any overload of function MyTemplatePoint3.templatedMethod'); end diff --git a/wrap/tests/expected2/Test.m b/wrap/tests/expected2/Test.m index ada5a868d..a36cbed48 100644 --- a/wrap/tests/expected2/Test.m +++ b/wrap/tests/expected2/Test.m @@ -34,11 +34,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(17, my_ptr); + geometry_wrapper(18, my_ptr); elseif nargin == 0 - my_ptr = geometry_wrapper(18); + my_ptr = geometry_wrapper(19); elseif nargin == 2 && isa(varargin{1},'double') && isa(varargin{2},'double') - my_ptr = geometry_wrapper(19, varargin{1}, varargin{2}); + my_ptr = geometry_wrapper(20, varargin{1}, varargin{2}); else error('Arguments do not match any overload of Test constructor'); end @@ -46,7 +46,7 @@ classdef Test < handle end function delete(obj) - geometry_wrapper(20, obj.ptr_Test); + geometry_wrapper(21, obj.ptr_Test); end function display(obj), obj.print(''); end @@ -57,7 +57,7 @@ classdef Test < handle % ARG_EIGENCONSTREF usage: arg_EigenConstRef(Matrix value) : returns void % 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') - geometry_wrapper(21, this, varargin{:}); + geometry_wrapper(22, this, varargin{:}); else error('Arguments do not match any overload of function Test.arg_EigenConstRef'); end @@ -66,32 +66,32 @@ classdef Test < handle function varargout = create_MixedPtrs(this, varargin) % CREATE_MIXEDPTRS usage: create_MixedPtrs() : returns pair< Test, Test > % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html - [ varargout{1} varargout{2} ] = geometry_wrapper(22, this, varargin{:}); + [ varargout{1} varargout{2} ] = geometry_wrapper(23, this, varargin{:}); end function varargout = create_ptrs(this, varargin) % CREATE_PTRS usage: create_ptrs() : returns pair< Test, Test > % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html - [ varargout{1} varargout{2} ] = geometry_wrapper(23, this, varargin{:}); + [ varargout{1} varargout{2} ] = geometry_wrapper(24, this, varargin{:}); end function varargout = print(this, varargin) % PRINT usage: print() : returns void % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html - geometry_wrapper(24, this, varargin{:}); + geometry_wrapper(25, this, varargin{:}); end function varargout = return_Point2Ptr(this, varargin) % RETURN_POINT2PTR usage: return_Point2Ptr(bool value) : returns gtsam::Point2 % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html - varargout{1} = geometry_wrapper(25, this, varargin{:}); + varargout{1} = geometry_wrapper(26, this, varargin{:}); end function varargout = return_Test(this, varargin) % RETURN_TEST usage: return_Test(Test value) : returns Test % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html if length(varargin) == 1 && isa(varargin{1},'Test') - varargout{1} = geometry_wrapper(26, this, varargin{:}); + varargout{1} = geometry_wrapper(27, this, varargin{:}); else error('Arguments do not match any overload of function Test.return_Test'); end @@ -101,7 +101,7 @@ classdef Test < handle % RETURN_TESTPTR usage: return_TestPtr(Test value) : returns Test % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html if length(varargin) == 1 && isa(varargin{1},'Test') - varargout{1} = geometry_wrapper(27, this, varargin{:}); + varargout{1} = geometry_wrapper(28, this, varargin{:}); else error('Arguments do not match any overload of function Test.return_TestPtr'); end @@ -110,20 +110,20 @@ classdef Test < handle function varargout = return_bool(this, varargin) % RETURN_BOOL usage: return_bool(bool value) : returns bool % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html - varargout{1} = geometry_wrapper(28, this, varargin{:}); + varargout{1} = geometry_wrapper(29, this, varargin{:}); end function varargout = return_double(this, varargin) % RETURN_DOUBLE usage: return_double(double value) : returns double % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html - varargout{1} = geometry_wrapper(29, this, varargin{:}); + varargout{1} = geometry_wrapper(30, this, varargin{:}); end function varargout = return_field(this, varargin) % RETURN_FIELD usage: return_field(Test t) : returns bool % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html if length(varargin) == 1 && isa(varargin{1},'Test') - varargout{1} = geometry_wrapper(30, this, varargin{:}); + varargout{1} = geometry_wrapper(31, this, varargin{:}); else error('Arguments do not match any overload of function Test.return_field'); end @@ -132,14 +132,14 @@ classdef Test < handle function varargout = return_int(this, varargin) % RETURN_INT usage: return_int(int value) : returns int % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html - varargout{1} = geometry_wrapper(31, this, varargin{:}); + varargout{1} = geometry_wrapper(32, this, varargin{:}); end function varargout = return_matrix1(this, varargin) % RETURN_MATRIX1 usage: return_matrix1(Matrix value) : returns Matrix % 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(32, this, varargin{:}); + varargout{1} = geometry_wrapper(33, this, varargin{:}); else error('Arguments do not match any overload of function Test.return_matrix1'); end @@ -149,7 +149,7 @@ classdef Test < handle % RETURN_MATRIX2 usage: return_matrix2(Matrix value) : returns Matrix % 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(33, this, varargin{:}); + varargout{1} = geometry_wrapper(34, this, varargin{:}); else error('Arguments do not match any overload of function Test.return_matrix2'); end @@ -158,8 +158,8 @@ classdef Test < handle function varargout = return_pair(this, varargin) % RETURN_PAIR usage: return_pair(Vector v, Matrix A) : returns pair< Vector, Matrix > % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html - if length(varargin) == 2 && isa(varargin{1},'double') && isa(varargin{2},'double') - [ varargout{1} varargout{2} ] = geometry_wrapper(34, this, varargin{:}); + if length(varargin) == 2 && isa(varargin{1},'double') && size(varargin{1},2)==1 && isa(varargin{2},'double') + [ varargout{1} varargout{2} ] = geometry_wrapper(35, this, varargin{:}); else error('Arguments do not match any overload of function Test.return_pair'); end @@ -169,7 +169,7 @@ classdef Test < handle % RETURN_PTRS usage: return_ptrs(Test p1, Test p2) : returns pair< Test, Test > % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html if length(varargin) == 2 && isa(varargin{1},'Test') && isa(varargin{2},'Test') - [ varargout{1} varargout{2} ] = geometry_wrapper(35, this, varargin{:}); + [ varargout{1} varargout{2} ] = geometry_wrapper(36, this, varargin{:}); else error('Arguments do not match any overload of function Test.return_ptrs'); end @@ -178,14 +178,14 @@ classdef Test < handle function varargout = return_size_t(this, varargin) % RETURN_SIZE_T usage: return_size_t(size_t value) : returns size_t % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html - varargout{1} = geometry_wrapper(36, this, varargin{:}); + varargout{1} = geometry_wrapper(37, this, varargin{:}); end function varargout = return_string(this, varargin) % RETURN_STRING usage: return_string(string value) : returns string % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html if length(varargin) == 1 && isa(varargin{1},'char') - varargout{1} = geometry_wrapper(37, this, varargin{:}); + varargout{1} = geometry_wrapper(38, this, varargin{:}); else error('Arguments do not match any overload of function Test.return_string'); end @@ -194,8 +194,8 @@ classdef Test < handle function varargout = return_vector1(this, varargin) % RETURN_VECTOR1 usage: return_vector1(Vector value) : returns Vector % 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(38, this, varargin{:}); + if length(varargin) == 1 && isa(varargin{1},'double') && size(varargin{1},2)==1 + varargout{1} = geometry_wrapper(39, this, varargin{:}); else error('Arguments do not match any overload of function Test.return_vector1'); end @@ -204,8 +204,8 @@ classdef Test < handle function varargout = return_vector2(this, varargin) % RETURN_VECTOR2 usage: return_vector2(Vector value) : returns Vector % 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(39, this, varargin{:}); + if length(varargin) == 1 && isa(varargin{1},'double') && size(varargin{1},2)==1 + varargout{1} = geometry_wrapper(40, this, varargin{:}); else error('Arguments do not match any overload of function Test.return_vector2'); end diff --git a/wrap/tests/expected2/aGlobalFunction.m b/wrap/tests/expected2/aGlobalFunction.m index e000338b6..d96662dc1 100644 --- a/wrap/tests/expected2/aGlobalFunction.m +++ b/wrap/tests/expected2/aGlobalFunction.m @@ -1,6 +1,6 @@ function varargout = aGlobalFunction(varargin) if length(varargin) == 0 - varargout{1} = geometry_wrapper(76, varargin{:}); + varargout{1} = geometry_wrapper(77, varargin{:}); else error('Arguments do not match any overload of function aGlobalFunction'); end diff --git a/wrap/tests/expected2/geometry_wrapper.cpp b/wrap/tests/expected2/geometry_wrapper.cpp index 22e1cf11a..dbe60bb63 100644 --- a/wrap/tests/expected2/geometry_wrapper.cpp +++ b/wrap/tests/expected2/geometry_wrapper.cpp @@ -181,7 +181,17 @@ void gtsamPoint2_dim_6(int nargout, mxArray *out[], int nargin, const mxArray *i out[0] = wrap< int >(obj->dim()); } -void gtsamPoint2_returnChar_7(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void gtsamPoint2_eigenArguments_7(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + typedef boost::shared_ptr Shared; + checkArguments("eigenArguments",nargout,nargin-1,2); + Shared 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_8(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr Shared; checkArguments("returnChar",nargout,nargin-1,0); @@ -189,7 +199,7 @@ void gtsamPoint2_returnChar_7(int nargout, mxArray *out[], int nargin, const mxA out[0] = wrap< char >(obj->returnChar()); } -void gtsamPoint2_vectorConfusion_8(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void gtsamPoint2_vectorConfusion_9(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr SharedVectorNotEigen; typedef boost::shared_ptr Shared; @@ -198,7 +208,7 @@ void gtsamPoint2_vectorConfusion_8(int nargout, mxArray *out[], int nargin, cons out[0] = wrap_shared_ptr(SharedVectorNotEigen(new VectorNotEigen(obj->vectorConfusion())),"VectorNotEigen", false); } -void gtsamPoint2_x_9(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void gtsamPoint2_x_10(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr Shared; checkArguments("x",nargout,nargin-1,0); @@ -206,7 +216,7 @@ void gtsamPoint2_x_9(int nargout, mxArray *out[], int nargin, const mxArray *in[ out[0] = wrap< double >(obj->x()); } -void gtsamPoint2_y_10(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void gtsamPoint2_y_11(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr Shared; checkArguments("y",nargout,nargin-1,0); @@ -214,7 +224,7 @@ void gtsamPoint2_y_10(int nargout, mxArray *out[], int nargin, const mxArray *in out[0] = wrap< double >(obj->y()); } -void gtsamPoint3_collectorInsertAndMakeBase_11(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void gtsamPoint3_collectorInsertAndMakeBase_12(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { mexAtExit(&_deleteAllObjects); typedef boost::shared_ptr Shared; @@ -223,7 +233,7 @@ void gtsamPoint3_collectorInsertAndMakeBase_11(int nargout, mxArray *out[], int collector_gtsamPoint3.insert(self); } -void gtsamPoint3_constructor_12(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void gtsamPoint3_constructor_13(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { mexAtExit(&_deleteAllObjects); typedef boost::shared_ptr Shared; @@ -237,7 +247,7 @@ void gtsamPoint3_constructor_12(int nargout, mxArray *out[], int nargin, const m *reinterpret_cast (mxGetData(out[0])) = self; } -void gtsamPoint3_deconstructor_13(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void gtsamPoint3_deconstructor_14(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr Shared; checkArguments("delete_gtsamPoint3",nargout,nargin,1); @@ -250,7 +260,7 @@ void gtsamPoint3_deconstructor_13(int nargout, mxArray *out[], int nargin, const } } -void gtsamPoint3_norm_14(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void gtsamPoint3_norm_15(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr Shared; checkArguments("norm",nargout,nargin-1,0); @@ -258,7 +268,7 @@ void gtsamPoint3_norm_14(int nargout, mxArray *out[], int nargin, const mxArray out[0] = wrap< double >(obj->norm()); } -void gtsamPoint3_StaticFunctionRet_15(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void gtsamPoint3_StaticFunctionRet_16(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr SharedPoint3; typedef boost::shared_ptr Shared; @@ -267,14 +277,14 @@ void gtsamPoint3_StaticFunctionRet_15(int nargout, mxArray *out[], int nargin, c out[0] = wrap_shared_ptr(SharedPoint3(new gtsam::Point3(gtsam::Point3::StaticFunctionRet(z))),"gtsam.Point3", false); } -void gtsamPoint3_staticFunction_16(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void gtsamPoint3_staticFunction_17(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr Shared; checkArguments("gtsamPoint3.staticFunction",nargout,nargin,0); out[0] = wrap< double >(gtsam::Point3::staticFunction()); } -void Test_collectorInsertAndMakeBase_17(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void Test_collectorInsertAndMakeBase_18(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { mexAtExit(&_deleteAllObjects); typedef boost::shared_ptr Shared; @@ -283,7 +293,7 @@ void Test_collectorInsertAndMakeBase_17(int nargout, mxArray *out[], int nargin, collector_Test.insert(self); } -void Test_constructor_18(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void Test_constructor_19(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { mexAtExit(&_deleteAllObjects); typedef boost::shared_ptr Shared; @@ -294,7 +304,7 @@ void Test_constructor_18(int nargout, mxArray *out[], int nargin, const mxArray *reinterpret_cast (mxGetData(out[0])) = self; } -void Test_constructor_19(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void Test_constructor_20(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { mexAtExit(&_deleteAllObjects); typedef boost::shared_ptr Shared; @@ -307,7 +317,7 @@ void Test_constructor_19(int nargout, mxArray *out[], int nargin, const mxArray *reinterpret_cast (mxGetData(out[0])) = self; } -void Test_deconstructor_20(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void Test_deconstructor_21(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr Shared; checkArguments("delete_Test",nargout,nargin,1); @@ -320,7 +330,7 @@ void Test_deconstructor_20(int nargout, mxArray *out[], int nargin, const mxArra } } -void Test_arg_EigenConstRef_21(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void Test_arg_EigenConstRef_22(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr Shared; checkArguments("arg_EigenConstRef",nargout,nargin-1,1); @@ -329,7 +339,7 @@ void Test_arg_EigenConstRef_21(int nargout, mxArray *out[], int nargin, const mx obj->arg_EigenConstRef(value); } -void Test_create_MixedPtrs_22(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void Test_create_MixedPtrs_23(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr SharedTest; typedef boost::shared_ptr SharedTest; @@ -341,7 +351,7 @@ void Test_create_MixedPtrs_22(int nargout, mxArray *out[], int nargin, const mxA out[1] = wrap_shared_ptr(pairResult.second,"Test", false); } -void Test_create_ptrs_23(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void Test_create_ptrs_24(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr SharedTest; typedef boost::shared_ptr SharedTest; @@ -353,7 +363,7 @@ void Test_create_ptrs_23(int nargout, mxArray *out[], int nargin, const mxArray out[1] = wrap_shared_ptr(pairResult.second,"Test", false); } -void Test_print_24(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void Test_print_25(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr Shared; checkArguments("print",nargout,nargin-1,0); @@ -361,7 +371,7 @@ void Test_print_24(int nargout, mxArray *out[], int nargin, const mxArray *in[]) obj->print(); } -void Test_return_Point2Ptr_25(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void Test_return_Point2Ptr_26(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr SharedPoint2; typedef boost::shared_ptr Shared; @@ -371,7 +381,7 @@ void Test_return_Point2Ptr_25(int nargout, mxArray *out[], int nargin, const mxA out[0] = wrap_shared_ptr(obj->return_Point2Ptr(value),"gtsam.Point2", false); } -void Test_return_Test_26(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void Test_return_Test_27(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr SharedTest; typedef boost::shared_ptr Shared; @@ -381,7 +391,7 @@ void Test_return_Test_26(int nargout, mxArray *out[], int nargin, const mxArray out[0] = wrap_shared_ptr(SharedTest(new Test(obj->return_Test(value))),"Test", false); } -void Test_return_TestPtr_27(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void Test_return_TestPtr_28(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr SharedTest; typedef boost::shared_ptr Shared; @@ -391,7 +401,7 @@ void Test_return_TestPtr_27(int nargout, mxArray *out[], int nargin, const mxArr out[0] = wrap_shared_ptr(obj->return_TestPtr(value),"Test", false); } -void Test_return_bool_28(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void Test_return_bool_29(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr Shared; checkArguments("return_bool",nargout,nargin-1,1); @@ -400,7 +410,7 @@ void Test_return_bool_28(int nargout, mxArray *out[], int nargin, const mxArray out[0] = wrap< bool >(obj->return_bool(value)); } -void Test_return_double_29(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void Test_return_double_30(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr Shared; checkArguments("return_double",nargout,nargin-1,1); @@ -409,7 +419,7 @@ void Test_return_double_29(int nargout, mxArray *out[], int nargin, const mxArra out[0] = wrap< double >(obj->return_double(value)); } -void Test_return_field_30(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void Test_return_field_31(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr Shared; checkArguments("return_field",nargout,nargin-1,1); @@ -418,7 +428,7 @@ void Test_return_field_30(int nargout, mxArray *out[], int nargin, const mxArray out[0] = wrap< bool >(obj->return_field(t)); } -void Test_return_int_31(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void Test_return_int_32(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr Shared; checkArguments("return_int",nargout,nargin-1,1); @@ -427,7 +437,7 @@ void Test_return_int_31(int nargout, mxArray *out[], int nargin, const mxArray * out[0] = wrap< int >(obj->return_int(value)); } -void Test_return_matrix1_32(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void Test_return_matrix1_33(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr Shared; checkArguments("return_matrix1",nargout,nargin-1,1); @@ -436,7 +446,7 @@ void Test_return_matrix1_32(int nargout, mxArray *out[], int nargin, const mxArr out[0] = wrap< Matrix >(obj->return_matrix1(value)); } -void Test_return_matrix2_33(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void Test_return_matrix2_34(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr Shared; checkArguments("return_matrix2",nargout,nargin-1,1); @@ -445,7 +455,7 @@ void Test_return_matrix2_33(int nargout, mxArray *out[], int nargin, const mxArr out[0] = wrap< Matrix >(obj->return_matrix2(value)); } -void Test_return_pair_34(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void Test_return_pair_35(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr Shared; checkArguments("return_pair",nargout,nargin-1,2); @@ -457,7 +467,7 @@ void Test_return_pair_34(int nargout, mxArray *out[], int nargin, const mxArray out[1] = wrap< Matrix >(pairResult.second); } -void Test_return_ptrs_35(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void Test_return_ptrs_36(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr SharedTest; typedef boost::shared_ptr SharedTest; @@ -471,7 +481,7 @@ void Test_return_ptrs_35(int nargout, mxArray *out[], int nargin, const mxArray out[1] = wrap_shared_ptr(pairResult.second,"Test", false); } -void Test_return_size_t_36(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void Test_return_size_t_37(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr Shared; checkArguments("return_size_t",nargout,nargin-1,1); @@ -480,7 +490,7 @@ void Test_return_size_t_36(int nargout, mxArray *out[], int nargin, const mxArra out[0] = wrap< size_t >(obj->return_size_t(value)); } -void Test_return_string_37(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void Test_return_string_38(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr Shared; checkArguments("return_string",nargout,nargin-1,1); @@ -489,7 +499,7 @@ void Test_return_string_37(int nargout, mxArray *out[], int nargin, const mxArra out[0] = wrap< string >(obj->return_string(value)); } -void Test_return_vector1_38(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void Test_return_vector1_39(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr Shared; checkArguments("return_vector1",nargout,nargin-1,1); @@ -498,7 +508,7 @@ void Test_return_vector1_38(int nargout, mxArray *out[], int nargin, const mxArr out[0] = wrap< Vector >(obj->return_vector1(value)); } -void Test_return_vector2_39(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void Test_return_vector2_40(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr Shared; checkArguments("return_vector2",nargout,nargin-1,1); @@ -507,7 +517,7 @@ void Test_return_vector2_39(int nargout, mxArray *out[], int nargin, const mxArr out[0] = wrap< Vector >(obj->return_vector2(value)); } -void MyBase_collectorInsertAndMakeBase_40(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void MyBase_collectorInsertAndMakeBase_41(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { mexAtExit(&_deleteAllObjects); typedef boost::shared_ptr Shared; @@ -516,7 +526,7 @@ void MyBase_collectorInsertAndMakeBase_40(int nargout, mxArray *out[], int nargi collector_MyBase.insert(self); } -void MyBase_upcastFromVoid_41(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { +void MyBase_upcastFromVoid_42(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])); @@ -525,7 +535,7 @@ void MyBase_upcastFromVoid_41(int nargout, mxArray *out[], int nargin, const mxA *reinterpret_cast(mxGetData(out[0])) = self; } -void MyBase_deconstructor_42(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void MyBase_deconstructor_43(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr Shared; checkArguments("delete_MyBase",nargout,nargin,1); @@ -538,7 +548,7 @@ void MyBase_deconstructor_42(int nargout, mxArray *out[], int nargin, const mxAr } } -void MyTemplatePoint2_collectorInsertAndMakeBase_43(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void MyTemplatePoint2_collectorInsertAndMakeBase_44(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { mexAtExit(&_deleteAllObjects); typedef boost::shared_ptr Shared; @@ -551,7 +561,7 @@ void MyTemplatePoint2_collectorInsertAndMakeBase_43(int nargout, mxArray *out[], *reinterpret_cast(mxGetData(out[0])) = new SharedBase(*self); } -void MyTemplatePoint2_upcastFromVoid_44(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { +void MyTemplatePoint2_upcastFromVoid_45(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])); @@ -560,7 +570,7 @@ void MyTemplatePoint2_upcastFromVoid_44(int nargout, mxArray *out[], int nargin, *reinterpret_cast(mxGetData(out[0])) = self; } -void MyTemplatePoint2_constructor_45(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void MyTemplatePoint2_constructor_46(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { mexAtExit(&_deleteAllObjects); typedef boost::shared_ptr Shared; @@ -575,7 +585,7 @@ void MyTemplatePoint2_constructor_45(int nargout, mxArray *out[], int nargin, co *reinterpret_cast(mxGetData(out[1])) = new SharedBase(*self); } -void MyTemplatePoint2_deconstructor_46(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void MyTemplatePoint2_deconstructor_47(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr Shared; checkArguments("delete_MyTemplatePoint2",nargout,nargin,1); @@ -588,7 +598,7 @@ void MyTemplatePoint2_deconstructor_46(int nargout, mxArray *out[], int nargin, } } -void MyTemplatePoint2_accept_T_47(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void MyTemplatePoint2_accept_T_48(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr Shared; checkArguments("accept_T",nargout,nargin-1,1); @@ -597,7 +607,7 @@ void MyTemplatePoint2_accept_T_47(int nargout, mxArray *out[], int nargin, const obj->accept_T(value); } -void MyTemplatePoint2_accept_Tptr_48(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void MyTemplatePoint2_accept_Tptr_49(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr Shared; checkArguments("accept_Tptr",nargout,nargin-1,1); @@ -606,7 +616,7 @@ void MyTemplatePoint2_accept_Tptr_48(int nargout, mxArray *out[], int nargin, co obj->accept_Tptr(value); } -void MyTemplatePoint2_create_MixedPtrs_49(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void MyTemplatePoint2_create_MixedPtrs_50(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr SharedPoint2; typedef boost::shared_ptr SharedPoint2; @@ -618,7 +628,7 @@ void MyTemplatePoint2_create_MixedPtrs_49(int nargout, mxArray *out[], int nargi out[1] = wrap_shared_ptr(pairResult.second,"gtsam.Point2", false); } -void MyTemplatePoint2_create_ptrs_50(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void MyTemplatePoint2_create_ptrs_51(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr SharedPoint2; typedef boost::shared_ptr SharedPoint2; @@ -630,7 +640,7 @@ void MyTemplatePoint2_create_ptrs_50(int nargout, mxArray *out[], int nargin, co out[1] = wrap_shared_ptr(pairResult.second,"gtsam.Point2", false); } -void MyTemplatePoint2_return_T_51(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void MyTemplatePoint2_return_T_52(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr SharedPoint2; typedef boost::shared_ptr Shared; @@ -640,7 +650,7 @@ void MyTemplatePoint2_return_T_51(int nargout, mxArray *out[], int nargin, const out[0] = wrap_shared_ptr(SharedPoint2(new gtsam::Point2(obj->return_T(value))),"gtsam.Point2", false); } -void MyTemplatePoint2_return_Tptr_52(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void MyTemplatePoint2_return_Tptr_53(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr SharedPoint2; typedef boost::shared_ptr Shared; @@ -650,7 +660,7 @@ void MyTemplatePoint2_return_Tptr_52(int nargout, mxArray *out[], int nargin, co out[0] = wrap_shared_ptr(obj->return_Tptr(value),"gtsam.Point2", false); } -void MyTemplatePoint2_return_ptrs_53(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void MyTemplatePoint2_return_ptrs_54(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr SharedPoint2; typedef boost::shared_ptr SharedPoint2; @@ -664,7 +674,7 @@ void MyTemplatePoint2_return_ptrs_53(int nargout, mxArray *out[], int nargin, co out[1] = wrap_shared_ptr(pairResult.second,"gtsam.Point2", false); } -void MyTemplatePoint2_templatedMethod_54(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void MyTemplatePoint2_templatedMethod_55(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr Shared; checkArguments("templatedMethodMatrix",nargout,nargin-1,1); @@ -673,7 +683,7 @@ void MyTemplatePoint2_templatedMethod_54(int nargout, mxArray *out[], int nargin obj->templatedMethod(t); } -void MyTemplatePoint2_templatedMethod_55(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void MyTemplatePoint2_templatedMethod_56(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr Shared; checkArguments("templatedMethodPoint2",nargout,nargin-1,1); @@ -682,7 +692,7 @@ void MyTemplatePoint2_templatedMethod_55(int nargout, mxArray *out[], int nargin obj->templatedMethod(t); } -void MyTemplatePoint2_templatedMethod_56(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void MyTemplatePoint2_templatedMethod_57(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr Shared; checkArguments("templatedMethodPoint3",nargout,nargin-1,1); @@ -691,7 +701,7 @@ void MyTemplatePoint2_templatedMethod_56(int nargout, mxArray *out[], int nargin obj->templatedMethod(t); } -void MyTemplatePoint2_templatedMethod_57(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void MyTemplatePoint2_templatedMethod_58(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr Shared; checkArguments("templatedMethodVector",nargout,nargin-1,1); @@ -700,7 +710,7 @@ void MyTemplatePoint2_templatedMethod_57(int nargout, mxArray *out[], int nargin obj->templatedMethod(t); } -void MyTemplatePoint3_collectorInsertAndMakeBase_58(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void MyTemplatePoint3_collectorInsertAndMakeBase_59(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { mexAtExit(&_deleteAllObjects); typedef boost::shared_ptr Shared; @@ -713,7 +723,7 @@ void MyTemplatePoint3_collectorInsertAndMakeBase_58(int nargout, mxArray *out[], *reinterpret_cast(mxGetData(out[0])) = new SharedBase(*self); } -void MyTemplatePoint3_upcastFromVoid_59(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { +void MyTemplatePoint3_upcastFromVoid_60(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])); @@ -722,7 +732,7 @@ void MyTemplatePoint3_upcastFromVoid_59(int nargout, mxArray *out[], int nargin, *reinterpret_cast(mxGetData(out[0])) = self; } -void MyTemplatePoint3_constructor_60(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void MyTemplatePoint3_constructor_61(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { mexAtExit(&_deleteAllObjects); typedef boost::shared_ptr Shared; @@ -737,7 +747,7 @@ void MyTemplatePoint3_constructor_60(int nargout, mxArray *out[], int nargin, co *reinterpret_cast(mxGetData(out[1])) = new SharedBase(*self); } -void MyTemplatePoint3_deconstructor_61(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void MyTemplatePoint3_deconstructor_62(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr Shared; checkArguments("delete_MyTemplatePoint3",nargout,nargin,1); @@ -750,7 +760,7 @@ void MyTemplatePoint3_deconstructor_61(int nargout, mxArray *out[], int nargin, } } -void MyTemplatePoint3_accept_T_62(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void MyTemplatePoint3_accept_T_63(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr Shared; checkArguments("accept_T",nargout,nargin-1,1); @@ -759,7 +769,7 @@ void MyTemplatePoint3_accept_T_62(int nargout, mxArray *out[], int nargin, const obj->accept_T(value); } -void MyTemplatePoint3_accept_Tptr_63(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void MyTemplatePoint3_accept_Tptr_64(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr Shared; checkArguments("accept_Tptr",nargout,nargin-1,1); @@ -768,7 +778,7 @@ void MyTemplatePoint3_accept_Tptr_63(int nargout, mxArray *out[], int nargin, co obj->accept_Tptr(value); } -void MyTemplatePoint3_create_MixedPtrs_64(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void MyTemplatePoint3_create_MixedPtrs_65(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr SharedPoint3; typedef boost::shared_ptr SharedPoint3; @@ -780,7 +790,7 @@ void MyTemplatePoint3_create_MixedPtrs_64(int nargout, mxArray *out[], int nargi out[1] = wrap_shared_ptr(pairResult.second,"gtsam.Point3", false); } -void MyTemplatePoint3_create_ptrs_65(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void MyTemplatePoint3_create_ptrs_66(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr SharedPoint3; typedef boost::shared_ptr SharedPoint3; @@ -792,7 +802,7 @@ void MyTemplatePoint3_create_ptrs_65(int nargout, mxArray *out[], int nargin, co out[1] = wrap_shared_ptr(pairResult.second,"gtsam.Point3", false); } -void MyTemplatePoint3_return_T_66(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void MyTemplatePoint3_return_T_67(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr SharedPoint3; typedef boost::shared_ptr Shared; @@ -802,7 +812,7 @@ void MyTemplatePoint3_return_T_66(int nargout, mxArray *out[], int nargin, const out[0] = wrap_shared_ptr(SharedPoint3(new gtsam::Point3(obj->return_T(value))),"gtsam.Point3", false); } -void MyTemplatePoint3_return_Tptr_67(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void MyTemplatePoint3_return_Tptr_68(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr SharedPoint3; typedef boost::shared_ptr Shared; @@ -812,7 +822,7 @@ void MyTemplatePoint3_return_Tptr_67(int nargout, mxArray *out[], int nargin, co out[0] = wrap_shared_ptr(obj->return_Tptr(value),"gtsam.Point3", false); } -void MyTemplatePoint3_return_ptrs_68(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void MyTemplatePoint3_return_ptrs_69(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr SharedPoint3; typedef boost::shared_ptr SharedPoint3; @@ -826,7 +836,7 @@ void MyTemplatePoint3_return_ptrs_68(int nargout, mxArray *out[], int nargin, co out[1] = wrap_shared_ptr(pairResult.second,"gtsam.Point3", false); } -void MyTemplatePoint3_templatedMethod_69(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void MyTemplatePoint3_templatedMethod_70(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr Shared; checkArguments("templatedMethodMatrix",nargout,nargin-1,1); @@ -835,7 +845,7 @@ void MyTemplatePoint3_templatedMethod_69(int nargout, mxArray *out[], int nargin obj->templatedMethod(t); } -void MyTemplatePoint3_templatedMethod_70(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void MyTemplatePoint3_templatedMethod_71(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr Shared; checkArguments("templatedMethodPoint2",nargout,nargin-1,1); @@ -844,7 +854,7 @@ void MyTemplatePoint3_templatedMethod_70(int nargout, mxArray *out[], int nargin obj->templatedMethod(t); } -void MyTemplatePoint3_templatedMethod_71(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void MyTemplatePoint3_templatedMethod_72(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr Shared; checkArguments("templatedMethodPoint3",nargout,nargin-1,1); @@ -853,7 +863,7 @@ void MyTemplatePoint3_templatedMethod_71(int nargout, mxArray *out[], int nargin obj->templatedMethod(t); } -void MyTemplatePoint3_templatedMethod_72(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void MyTemplatePoint3_templatedMethod_73(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr Shared; checkArguments("templatedMethodVector",nargout,nargin-1,1); @@ -862,7 +872,7 @@ void MyTemplatePoint3_templatedMethod_72(int nargout, mxArray *out[], int nargin obj->templatedMethod(t); } -void MyFactorPosePoint2_collectorInsertAndMakeBase_73(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void MyFactorPosePoint2_collectorInsertAndMakeBase_74(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { mexAtExit(&_deleteAllObjects); typedef boost::shared_ptr Shared; @@ -871,7 +881,7 @@ void MyFactorPosePoint2_collectorInsertAndMakeBase_73(int nargout, mxArray *out[ collector_MyFactorPosePoint2.insert(self); } -void MyFactorPosePoint2_constructor_74(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void MyFactorPosePoint2_constructor_75(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { mexAtExit(&_deleteAllObjects); typedef boost::shared_ptr Shared; @@ -886,7 +896,7 @@ void MyFactorPosePoint2_constructor_74(int nargout, mxArray *out[], int nargin, *reinterpret_cast (mxGetData(out[0])) = self; } -void MyFactorPosePoint2_deconstructor_75(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void MyFactorPosePoint2_deconstructor_76(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr Shared; checkArguments("delete_MyFactorPosePoint2",nargout,nargin,1); @@ -899,18 +909,18 @@ void MyFactorPosePoint2_deconstructor_75(int nargout, mxArray *out[], int nargin } } -void aGlobalFunction_76(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void aGlobalFunction_77(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { checkArguments("aGlobalFunction",nargout,nargin,0); out[0] = wrap< Vector >(aGlobalFunction()); } -void overloadedGlobalFunction_77(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void overloadedGlobalFunction_78(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_78(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void overloadedGlobalFunction_79(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { checkArguments("overloadedGlobalFunction",nargout,nargin,2); int a = unwrap< int >(in[0]); @@ -951,148 +961,148 @@ void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) gtsamPoint2_dim_6(nargout, out, nargin-1, in+1); break; case 7: - gtsamPoint2_returnChar_7(nargout, out, nargin-1, in+1); + gtsamPoint2_eigenArguments_7(nargout, out, nargin-1, in+1); break; case 8: - gtsamPoint2_vectorConfusion_8(nargout, out, nargin-1, in+1); + gtsamPoint2_returnChar_8(nargout, out, nargin-1, in+1); break; case 9: - gtsamPoint2_x_9(nargout, out, nargin-1, in+1); + gtsamPoint2_vectorConfusion_9(nargout, out, nargin-1, in+1); break; case 10: - gtsamPoint2_y_10(nargout, out, nargin-1, in+1); + gtsamPoint2_x_10(nargout, out, nargin-1, in+1); break; case 11: - gtsamPoint3_collectorInsertAndMakeBase_11(nargout, out, nargin-1, in+1); + gtsamPoint2_y_11(nargout, out, nargin-1, in+1); break; case 12: - gtsamPoint3_constructor_12(nargout, out, nargin-1, in+1); + gtsamPoint3_collectorInsertAndMakeBase_12(nargout, out, nargin-1, in+1); break; case 13: - gtsamPoint3_deconstructor_13(nargout, out, nargin-1, in+1); + gtsamPoint3_constructor_13(nargout, out, nargin-1, in+1); break; case 14: - gtsamPoint3_norm_14(nargout, out, nargin-1, in+1); + gtsamPoint3_deconstructor_14(nargout, out, nargin-1, in+1); break; case 15: - gtsamPoint3_StaticFunctionRet_15(nargout, out, nargin-1, in+1); + gtsamPoint3_norm_15(nargout, out, nargin-1, in+1); break; case 16: - gtsamPoint3_staticFunction_16(nargout, out, nargin-1, in+1); + gtsamPoint3_StaticFunctionRet_16(nargout, out, nargin-1, in+1); break; case 17: - Test_collectorInsertAndMakeBase_17(nargout, out, nargin-1, in+1); + gtsamPoint3_staticFunction_17(nargout, out, nargin-1, in+1); break; case 18: - Test_constructor_18(nargout, out, nargin-1, in+1); + Test_collectorInsertAndMakeBase_18(nargout, out, nargin-1, in+1); break; case 19: Test_constructor_19(nargout, out, nargin-1, in+1); break; case 20: - Test_deconstructor_20(nargout, out, nargin-1, in+1); + Test_constructor_20(nargout, out, nargin-1, in+1); break; case 21: - Test_arg_EigenConstRef_21(nargout, out, nargin-1, in+1); + Test_deconstructor_21(nargout, out, nargin-1, in+1); break; case 22: - Test_create_MixedPtrs_22(nargout, out, nargin-1, in+1); + Test_arg_EigenConstRef_22(nargout, out, nargin-1, in+1); break; case 23: - Test_create_ptrs_23(nargout, out, nargin-1, in+1); + Test_create_MixedPtrs_23(nargout, out, nargin-1, in+1); break; case 24: - Test_print_24(nargout, out, nargin-1, in+1); + Test_create_ptrs_24(nargout, out, nargin-1, in+1); break; case 25: - Test_return_Point2Ptr_25(nargout, out, nargin-1, in+1); + Test_print_25(nargout, out, nargin-1, in+1); break; case 26: - Test_return_Test_26(nargout, out, nargin-1, in+1); + Test_return_Point2Ptr_26(nargout, out, nargin-1, in+1); break; case 27: - Test_return_TestPtr_27(nargout, out, nargin-1, in+1); + Test_return_Test_27(nargout, out, nargin-1, in+1); break; case 28: - Test_return_bool_28(nargout, out, nargin-1, in+1); + Test_return_TestPtr_28(nargout, out, nargin-1, in+1); break; case 29: - Test_return_double_29(nargout, out, nargin-1, in+1); + Test_return_bool_29(nargout, out, nargin-1, in+1); break; case 30: - Test_return_field_30(nargout, out, nargin-1, in+1); + Test_return_double_30(nargout, out, nargin-1, in+1); break; case 31: - Test_return_int_31(nargout, out, nargin-1, in+1); + Test_return_field_31(nargout, out, nargin-1, in+1); break; case 32: - Test_return_matrix1_32(nargout, out, nargin-1, in+1); + Test_return_int_32(nargout, out, nargin-1, in+1); break; case 33: - Test_return_matrix2_33(nargout, out, nargin-1, in+1); + Test_return_matrix1_33(nargout, out, nargin-1, in+1); break; case 34: - Test_return_pair_34(nargout, out, nargin-1, in+1); + Test_return_matrix2_34(nargout, out, nargin-1, in+1); break; case 35: - Test_return_ptrs_35(nargout, out, nargin-1, in+1); + Test_return_pair_35(nargout, out, nargin-1, in+1); break; case 36: - Test_return_size_t_36(nargout, out, nargin-1, in+1); + Test_return_ptrs_36(nargout, out, nargin-1, in+1); break; case 37: - Test_return_string_37(nargout, out, nargin-1, in+1); + Test_return_size_t_37(nargout, out, nargin-1, in+1); break; case 38: - Test_return_vector1_38(nargout, out, nargin-1, in+1); + Test_return_string_38(nargout, out, nargin-1, in+1); break; case 39: - Test_return_vector2_39(nargout, out, nargin-1, in+1); + Test_return_vector1_39(nargout, out, nargin-1, in+1); break; case 40: - MyBase_collectorInsertAndMakeBase_40(nargout, out, nargin-1, in+1); + Test_return_vector2_40(nargout, out, nargin-1, in+1); break; case 41: - MyBase_upcastFromVoid_41(nargout, out, nargin-1, in+1); + MyBase_collectorInsertAndMakeBase_41(nargout, out, nargin-1, in+1); break; case 42: - MyBase_deconstructor_42(nargout, out, nargin-1, in+1); + MyBase_upcastFromVoid_42(nargout, out, nargin-1, in+1); break; case 43: - MyTemplatePoint2_collectorInsertAndMakeBase_43(nargout, out, nargin-1, in+1); + MyBase_deconstructor_43(nargout, out, nargin-1, in+1); break; case 44: - MyTemplatePoint2_upcastFromVoid_44(nargout, out, nargin-1, in+1); + MyTemplatePoint2_collectorInsertAndMakeBase_44(nargout, out, nargin-1, in+1); break; case 45: - MyTemplatePoint2_constructor_45(nargout, out, nargin-1, in+1); + MyTemplatePoint2_upcastFromVoid_45(nargout, out, nargin-1, in+1); break; case 46: - MyTemplatePoint2_deconstructor_46(nargout, out, nargin-1, in+1); + MyTemplatePoint2_constructor_46(nargout, out, nargin-1, in+1); break; case 47: - MyTemplatePoint2_accept_T_47(nargout, out, nargin-1, in+1); + MyTemplatePoint2_deconstructor_47(nargout, out, nargin-1, in+1); break; case 48: - MyTemplatePoint2_accept_Tptr_48(nargout, out, nargin-1, in+1); + MyTemplatePoint2_accept_T_48(nargout, out, nargin-1, in+1); break; case 49: - MyTemplatePoint2_create_MixedPtrs_49(nargout, out, nargin-1, in+1); + MyTemplatePoint2_accept_Tptr_49(nargout, out, nargin-1, in+1); break; case 50: - MyTemplatePoint2_create_ptrs_50(nargout, out, nargin-1, in+1); + MyTemplatePoint2_create_MixedPtrs_50(nargout, out, nargin-1, in+1); break; case 51: - MyTemplatePoint2_return_T_51(nargout, out, nargin-1, in+1); + MyTemplatePoint2_create_ptrs_51(nargout, out, nargin-1, in+1); break; case 52: - MyTemplatePoint2_return_Tptr_52(nargout, out, nargin-1, in+1); + MyTemplatePoint2_return_T_52(nargout, out, nargin-1, in+1); break; case 53: - MyTemplatePoint2_return_ptrs_53(nargout, out, nargin-1, in+1); + MyTemplatePoint2_return_Tptr_53(nargout, out, nargin-1, in+1); break; case 54: - MyTemplatePoint2_templatedMethod_54(nargout, out, nargin-1, in+1); + MyTemplatePoint2_return_ptrs_54(nargout, out, nargin-1, in+1); break; case 55: MyTemplatePoint2_templatedMethod_55(nargout, out, nargin-1, in+1); @@ -1104,40 +1114,40 @@ void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) MyTemplatePoint2_templatedMethod_57(nargout, out, nargin-1, in+1); break; case 58: - MyTemplatePoint3_collectorInsertAndMakeBase_58(nargout, out, nargin-1, in+1); + MyTemplatePoint2_templatedMethod_58(nargout, out, nargin-1, in+1); break; case 59: - MyTemplatePoint3_upcastFromVoid_59(nargout, out, nargin-1, in+1); + MyTemplatePoint3_collectorInsertAndMakeBase_59(nargout, out, nargin-1, in+1); break; case 60: - MyTemplatePoint3_constructor_60(nargout, out, nargin-1, in+1); + MyTemplatePoint3_upcastFromVoid_60(nargout, out, nargin-1, in+1); break; case 61: - MyTemplatePoint3_deconstructor_61(nargout, out, nargin-1, in+1); + MyTemplatePoint3_constructor_61(nargout, out, nargin-1, in+1); break; case 62: - MyTemplatePoint3_accept_T_62(nargout, out, nargin-1, in+1); + MyTemplatePoint3_deconstructor_62(nargout, out, nargin-1, in+1); break; case 63: - MyTemplatePoint3_accept_Tptr_63(nargout, out, nargin-1, in+1); + MyTemplatePoint3_accept_T_63(nargout, out, nargin-1, in+1); break; case 64: - MyTemplatePoint3_create_MixedPtrs_64(nargout, out, nargin-1, in+1); + MyTemplatePoint3_accept_Tptr_64(nargout, out, nargin-1, in+1); break; case 65: - MyTemplatePoint3_create_ptrs_65(nargout, out, nargin-1, in+1); + MyTemplatePoint3_create_MixedPtrs_65(nargout, out, nargin-1, in+1); break; case 66: - MyTemplatePoint3_return_T_66(nargout, out, nargin-1, in+1); + MyTemplatePoint3_create_ptrs_66(nargout, out, nargin-1, in+1); break; case 67: - MyTemplatePoint3_return_Tptr_67(nargout, out, nargin-1, in+1); + MyTemplatePoint3_return_T_67(nargout, out, nargin-1, in+1); break; case 68: - MyTemplatePoint3_return_ptrs_68(nargout, out, nargin-1, in+1); + MyTemplatePoint3_return_Tptr_68(nargout, out, nargin-1, in+1); break; case 69: - MyTemplatePoint3_templatedMethod_69(nargout, out, nargin-1, in+1); + MyTemplatePoint3_return_ptrs_69(nargout, out, nargin-1, in+1); break; case 70: MyTemplatePoint3_templatedMethod_70(nargout, out, nargin-1, in+1); @@ -1149,23 +1159,26 @@ void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) MyTemplatePoint3_templatedMethod_72(nargout, out, nargin-1, in+1); break; case 73: - MyFactorPosePoint2_collectorInsertAndMakeBase_73(nargout, out, nargin-1, in+1); + MyTemplatePoint3_templatedMethod_73(nargout, out, nargin-1, in+1); break; case 74: - MyFactorPosePoint2_constructor_74(nargout, out, nargin-1, in+1); + MyFactorPosePoint2_collectorInsertAndMakeBase_74(nargout, out, nargin-1, in+1); break; case 75: - MyFactorPosePoint2_deconstructor_75(nargout, out, nargin-1, in+1); + MyFactorPosePoint2_constructor_75(nargout, out, nargin-1, in+1); break; case 76: - aGlobalFunction_76(nargout, out, nargin-1, in+1); + MyFactorPosePoint2_deconstructor_76(nargout, out, nargin-1, in+1); break; case 77: - overloadedGlobalFunction_77(nargout, out, nargin-1, in+1); + aGlobalFunction_77(nargout, out, nargin-1, in+1); break; case 78: overloadedGlobalFunction_78(nargout, out, nargin-1, in+1); break; + case 79: + overloadedGlobalFunction_79(nargout, out, nargin-1, in+1); + break; } } catch(const std::exception& e) { mexErrMsgTxt(("Exception from gtsam:\n" + std::string(e.what()) + "\n").c_str()); diff --git a/wrap/tests/expected2/overloadedGlobalFunction.m b/wrap/tests/expected2/overloadedGlobalFunction.m index fb912a880..7dd7317ab 100644 --- a/wrap/tests/expected2/overloadedGlobalFunction.m +++ b/wrap/tests/expected2/overloadedGlobalFunction.m @@ -1,8 +1,8 @@ function varargout = overloadedGlobalFunction(varargin) if length(varargin) == 1 && isa(varargin{1},'numeric') - varargout{1} = geometry_wrapper(77, varargin{:}); - elseif length(varargin) == 2 && isa(varargin{1},'numeric') && isa(varargin{2},'double') varargout{1} = geometry_wrapper(78, varargin{:}); + elseif length(varargin) == 2 && isa(varargin{1},'numeric') && isa(varargin{2},'double') + varargout{1} = geometry_wrapper(79, varargin{:}); else error('Arguments do not match any overload of function overloadedGlobalFunction'); end diff --git a/wrap/tests/geometry.h b/wrap/tests/geometry.h index c335df924..3fec21ab9 100644 --- a/wrap/tests/geometry.h +++ b/wrap/tests/geometry.h @@ -14,6 +14,7 @@ class Point2 { char returnChar() const; void argChar(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 diff --git a/wrap/tests/testWrap.cpp b/wrap/tests/testWrap.cpp index 0645fb407..c1f6f091e 100644 --- a/wrap/tests/testWrap.cpp +++ b/wrap/tests/testWrap.cpp @@ -184,7 +184,7 @@ TEST( wrap, Geometry ) { Class cls = module.classes.at(0); EXPECT(assert_equal("Point2", cls.name)); EXPECT_LONGS_EQUAL(2, cls.constructor.nrOverloads()); - EXPECT_LONGS_EQUAL(7, cls.nrMethods()); + EXPECT_LONGS_EQUAL(8, cls.nrMethods()); { // char returnChar() const; From b12255285b7840ba0b98bba4b47e527240ddc675 Mon Sep 17 00:00:00 2001 From: dellaert Date: Sun, 30 Nov 2014 00:13:29 +0100 Subject: [PATCH 029/126] More clear than operator overload --- wrap/Argument.cpp | 2 +- wrap/ReturnValue.cpp | 4 ++-- wrap/TemplateSubstitution.h | 4 ++-- 3 files changed, 5 insertions(+), 5 deletions(-) diff --git a/wrap/Argument.cpp b/wrap/Argument.cpp index 2350a77d7..6a5675a44 100644 --- a/wrap/Argument.cpp +++ b/wrap/Argument.cpp @@ -32,7 +32,7 @@ using namespace wrap; /* ************************************************************************* */ Argument Argument::expandTemplate(const TemplateSubstitution& ts) const { Argument instArg = *this; - instArg.type = ts(type); + instArg.type = ts.tryToSubstitite(type); return instArg; } diff --git a/wrap/ReturnValue.cpp b/wrap/ReturnValue.cpp index 54e585cad..596acb2c3 100644 --- a/wrap/ReturnValue.cpp +++ b/wrap/ReturnValue.cpp @@ -17,9 +17,9 @@ using namespace wrap; /* ************************************************************************* */ ReturnValue ReturnValue::expandTemplate(const TemplateSubstitution& ts) const { ReturnValue instRetVal = *this; - instRetVal.type1 = ts(type1); + instRetVal.type1 = ts.tryToSubstitite(type1); if (isPair) - instRetVal.type2 = ts(type2); + instRetVal.type2 = ts.tryToSubstitite(type2); return instRetVal; } diff --git a/wrap/TemplateSubstitution.h b/wrap/TemplateSubstitution.h index b20a1af6f..52c29f571 100644 --- a/wrap/TemplateSubstitution.h +++ b/wrap/TemplateSubstitution.h @@ -44,7 +44,7 @@ public: } // Substitute if needed - Qualified operator()(const Qualified& type) const { + Qualified tryToSubstitite(const Qualified& type) const { if (type.name == templateArg_ && type.namespaces.empty()) return qualifiedType_; else if (type.name == "This") @@ -54,7 +54,7 @@ public: } // Substitute if needed - ReturnType operator()(const ReturnType& type) const { + ReturnType tryToSubstitite(const ReturnType& type) const { ReturnType instType = type; if (type.name == templateArg_ && type.namespaces.empty()) instType.rename(qualifiedType_); From 3cffb731559df2c2f56b5750b8e4a7d8bdd78279 Mon Sep 17 00:00:00 2001 From: dellaert Date: Sun, 30 Nov 2014 10:36:52 +0100 Subject: [PATCH 030/126] Added MATLAB tests --- gtsam.h | 11 ++++----- matlab/gtsam_tests/.gitignore | 1 + matlab/gtsam_tests/testValues.m | 40 +++++++++++++++++++++++++++++++++ matlab/gtsam_tests/test_gtsam.m | 3 +++ 4 files changed, 48 insertions(+), 7 deletions(-) create mode 100644 matlab/gtsam_tests/.gitignore create mode 100644 matlab/gtsam_tests/testValues.m diff --git a/gtsam.h b/gtsam.h index b40913229..96d51117a 100644 --- a/gtsam.h +++ b/gtsam.h @@ -1739,7 +1739,7 @@ class Values { void insert(size_t j, const gtsam::EssentialMatrix& t); void insert(size_t j, const gtsam::imuBias::ConstantBias& t); void insert(size_t j, Vector t); - void insert(size_t j, Matrix t); //git/gtsam/gtsam/base/Manifold.h:254:1: error: invalid application of ‘sizeof’ to incomplete type ‘boost::STATIC_ASSERTION_FAILURE’ + void insert(size_t j, Matrix t); void update(size_t j, const gtsam::Point2& t); void update(size_t j, const gtsam::Point3& t); @@ -1755,8 +1755,7 @@ class Values { void update(size_t j, Vector t); void update(size_t j, Matrix t); - template // Parse Error + template T at(size_t j); }; @@ -2154,9 +2153,7 @@ class NonlinearISAM { #include #include -template // Parse Error +template virtual class PriorFactor : gtsam::NoiseModelFactor { PriorFactor(size_t key, const T& prior, const gtsam::noiseModel::Base* noiseModel); T prior() const; @@ -2167,7 +2164,7 @@ virtual class PriorFactor : gtsam::NoiseModelFactor { #include -template // Parse Error +template virtual class BetweenFactor : gtsam::NoiseModelFactor { BetweenFactor(size_t key1, size_t key2, const T& relativePose, const gtsam::noiseModel::Base* noiseModel); T measured() const; diff --git a/matlab/gtsam_tests/.gitignore b/matlab/gtsam_tests/.gitignore new file mode 100644 index 000000000..6d725d9bc --- /dev/null +++ b/matlab/gtsam_tests/.gitignore @@ -0,0 +1 @@ +*.m~ diff --git a/matlab/gtsam_tests/testValues.m b/matlab/gtsam_tests/testValues.m new file mode 100644 index 000000000..ce2ae9d7e --- /dev/null +++ b/matlab/gtsam_tests/testValues.m @@ -0,0 +1,40 @@ +% test wrapping of Values +import gtsam.*; + +values = Values; +E = EssentialMatrix(Rot3,Unit3); +tol = 1e-9; + +values.insert(0, Point2); +values.insert(1, Point3); +values.insert(2, Rot2); +values.insert(3, Pose2); +values.insert(4, Rot3); +values.insert(5, Pose3); +values.insert(6, Cal3_S2); +values.insert(7, Cal3DS2); +values.insert(8, Cal3Bundler); +values.insert(9, E); +values.insert(10, imuBias.ConstantBias); + +% special cases for Vector and Matrix: +values.insert(11, [1;2;3]); +values.insert(12, [1 2;3 4]); + +EXPECT('at',values.atPoint2(0).equals(Point2,tol)); +EXPECT('at',values.atPoint3(1).equals(Point3,tol)); +EXPECT('at',values.atRot2(2).equals(Rot2,tol)); +EXPECT('at',values.atPose2(3).equals(Pose2,tol)); +EXPECT('at',values.atRot3(4).equals(Rot3,tol)); +EXPECT('at',values.atPose3(5).equals(Pose3,tol)); +EXPECT('at',values.atCal3_S2(6).equals(Cal3_S2,tol)); +EXPECT('at',values.atCal3DS2(7).equals(Cal3DS2,tol)); +EXPECT('at',values.atCal3Bundler(8).equals(Cal3Bundler,tol)); +EXPECT('at',values.atEssentialMatrix(9).equals(E,tol)); +EXPECT('at',values.atConstantBias(10).equals(imuBias.ConstantBias,tol)); + +% special cases for Vector and Matrix: +actualVector = values.atVector(11); +EQUALITY('at',[1 2;3 4],actualVector,tol); +actualMatrix = values.atMatrix(12); +EQUALITY('at',[1 2;3 4],actualMatrix,tol); diff --git a/matlab/gtsam_tests/test_gtsam.m b/matlab/gtsam_tests/test_gtsam.m index e3705948d..e08019610 100644 --- a/matlab/gtsam_tests/test_gtsam.m +++ b/matlab/gtsam_tests/test_gtsam.m @@ -1,5 +1,8 @@ % Test runner script - runs each test +display 'Starting: testValues' +testValues + display 'Starting: testJacobianFactor' testJacobianFactor From 74361ce64acb688b0928cfb72bd88c525a767052 Mon Sep 17 00:00:00 2001 From: dellaert Date: Sun, 30 Nov 2014 10:37:25 +0100 Subject: [PATCH 031/126] Test with argument templated --- wrap/tests/geometry.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/wrap/tests/geometry.h b/wrap/tests/geometry.h index 3fec21ab9..0646ff456 100644 --- a/wrap/tests/geometry.h +++ b/wrap/tests/geometry.h @@ -106,7 +106,7 @@ virtual class MyTemplate : MyBase { MyTemplate(); template - void templatedMethod(const ARG& t); + ARG templatedMethod(const ARG& t); // Stress test templates and pointer combinations void accept_T(const T& value) const; From 14ef786dfe23099e85482532df7aef6def0d1b7f Mon Sep 17 00:00:00 2001 From: dellaert Date: Sun, 30 Nov 2014 10:38:24 +0100 Subject: [PATCH 032/126] Removing empty in favor of boost::optional --- wrap/Class.cpp | 38 +++++++++++++++--------------- wrap/Class.h | 3 ++- wrap/Constructor.cpp | 6 ++--- wrap/Constructor.h | 4 ++-- wrap/Function.cpp | 9 +++----- wrap/Function.h | 11 +++++---- wrap/Method.cpp | 7 +++--- wrap/Method.h | 3 +-- wrap/MethodBase.cpp | 10 ++++---- wrap/MethodBase.h | 6 ++--- wrap/Qualified.h | 45 ++++++++++++++++++++++++++++-------- wrap/ReturnType.cpp | 4 ++-- wrap/ReturnType.h | 12 +++------- wrap/ReturnValue.cpp | 2 +- wrap/ReturnValue.h | 2 +- wrap/StaticMethod.cpp | 7 +++--- wrap/StaticMethod.h | 3 +-- wrap/TypeAttributesTable.cpp | 8 +++---- wrap/tests/testWrap.cpp | 18 +++++++-------- 19 files changed, 105 insertions(+), 93 deletions(-) diff --git a/wrap/Class.cpp b/wrap/Class.cpp index 93135498f..d8b18a0b4 100644 --- a/wrap/Class.cpp +++ b/wrap/Class.cpp @@ -29,11 +29,9 @@ #include #include #include // std::ostream_iterator - //#include // on Linux GCC: fails with error regarding needing C++0x std flags //#include // same failure as above #include // works on Linux GCC - using namespace std; using namespace wrap; @@ -67,12 +65,11 @@ void Class::matlab_proxy(Str toolboxPath, Str wrapperName, const string matlabQualName = qualifiedName("."); const string matlabUniqueName = qualifiedName(); const string cppName = qualifiedName("::"); - const string matlabBaseName = qualifiedParent.qualifiedName("."); - const string cppBaseName = qualifiedParent.qualifiedName("::"); // emit class proxy code // we want our class to inherit the handle class for memory purposes - const string parent = qualifiedParent.empty() ? "handle" : matlabBaseName; + const string parent = + parentClass ? "handle" : parentClass->qualifiedName("."); comment_fragment(proxyFile); proxyFile.oss << "classdef " << name << " < " << parent << endl; proxyFile.oss << " properties\n"; @@ -94,11 +91,14 @@ void Class::matlab_proxy(Str toolboxPath, Str wrapperName, wrapperFile.oss << "\n"; // Regular constructors + boost::optional cppBaseName; + if (parentClass) + cppBaseName = parentClass->qualifiedName("::"); for (size_t i = 0; i < constructor.nrOverloads(); i++) { ArgumentList args = constructor.argumentList(i); const int id = (int) functionNames.size(); - constructor.proxy_fragment(proxyFile, wrapperName, !qualifiedParent.empty(), - id, args); + constructor.proxy_fragment(proxyFile, wrapperName, (bool) parentClass, id, + args); const string wrapFunctionName = constructor.wrapper_fragment(wrapperFile, cppName, matlabUniqueName, cppBaseName, id, args); wrapperFile.oss << "\n"; @@ -108,9 +108,9 @@ void Class::matlab_proxy(Str toolboxPath, Str wrapperName, proxyFile.oss << " error('Arguments do not match any overload of " << matlabQualName << " constructor');\n"; proxyFile.oss << " end\n"; - if (!qualifiedParent.empty()) - proxyFile.oss << " obj = obj@" << matlabBaseName << "(uint64(" - << ptr_constructor_key << "), base_ptr);\n"; + if (parentClass) + proxyFile.oss << " obj = obj@" << parentClass->qualifiedName(".") + << "(uint64(" << ptr_constructor_key << "), base_ptr);\n"; proxyFile.oss << " obj.ptr_" << matlabUniqueName << " = my_ptr;\n"; proxyFile.oss << " end\n\n"; @@ -170,7 +170,6 @@ void Class::pointer_constructor_fragments(FileWriter& proxyFile, const string matlabUniqueName = qualifiedName(); const string cppName = qualifiedName("::"); - const string baseCppName = qualifiedParent.qualifiedName("::"); const int collectorInsertId = (int) functionNames.size(); const string collectorInsertFunctionName = matlabUniqueName @@ -207,7 +206,7 @@ void Class::pointer_constructor_fragments(FileWriter& proxyFile, } else { proxyFile.oss << " my_ptr = varargin{2};\n"; } - if (qualifiedParent.empty()) // If this class has a base class, we'll get a base class pointer back + if (!parentClass) // If this class has a base class, we'll get a base class pointer back proxyFile.oss << " "; else proxyFile.oss << " base_ptr = "; @@ -230,7 +229,8 @@ void Class::pointer_constructor_fragments(FileWriter& proxyFile, // Add to collector wrapperFile.oss << " collector_" << matlabUniqueName << ".insert(self);\n"; // If we have a base class, return the base class pointer (MATLAB will call the base class collectorInsertAndMakeBase to add this to the collector and recurse the heirarchy) - if (!qualifiedParent.empty()) { + if (parentClass) { + const string baseCppName = parentClass->qualifiedName("::"); wrapperFile.oss << "\n"; wrapperFile.oss << " typedef boost::shared_ptr<" << baseCppName << "> SharedBase;\n"; @@ -297,7 +297,7 @@ void Class::addMethod(bool verbose, bool is_const, Str methodName, // Create method to expand // For all values of the template argument, create a new method BOOST_FOREACH(const Qualified& instName, templateArgValues) { - const TemplateSubstitution ts(templateArgName, instName, this->name); + const TemplateSubstitution ts(templateArgName, instName, *this); // substitute template in arguments ArgumentList expandedArgs = argumentList.expandTemplate(ts); // do the same for return type @@ -353,10 +353,10 @@ void Class::verifyAll(vector& validTypes, bool& hasSerialiable) const { verifyReturnTypes(validTypes, methods_); // verify parents - if (!qualifiedParent.empty() + if (parentClass && find(validTypes.begin(), validTypes.end(), - qualifiedParent.qualifiedName("::")) == validTypes.end()) - throw DependencyMissing(qualifiedParent.qualifiedName("::"), + parentClass->qualifiedName("::")) == validTypes.end()) + throw DependencyMissing(parentClass->qualifiedName("::"), qualifiedName("::")); } @@ -364,12 +364,12 @@ void Class::verifyAll(vector& validTypes, bool& hasSerialiable) const { void Class::appendInheritedMethods(const Class& cls, const vector& classes) { - if (!cls.qualifiedParent.empty()) { + if (cls.parentClass) { // Find parent BOOST_FOREACH(const Class& parent, classes) { // We found a parent class for our parent, TODO improve ! - if (parent.name == cls.qualifiedParent.name) { + if (parent.name == cls.parentClass->name) { methods_.insert(parent.methods_.begin(), parent.methods_.end()); appendInheritedMethods(parent, classes); } diff --git a/wrap/Class.h b/wrap/Class.h index 9e4dff13d..f1b0ba55a 100644 --- a/wrap/Class.h +++ b/wrap/Class.h @@ -27,6 +27,7 @@ #include #include +#include #include #include @@ -53,7 +54,7 @@ public: bool isVirtual; ///< Whether the class is part of a virtual inheritance chain bool isSerializable; ///< Whether we can use boost.serialization to serialize the class - creates exports bool hasSerialization; ///< Whether we should create the serialization functions - Qualified qualifiedParent; ///< The *single* parent + boost::optional parentClass; ///< The *single* parent Constructor constructor; ///< Class constructors Deconstructor deconstructor; ///< Deconstructor to deallocate C++ object bool verbose_; ///< verbose flag diff --git a/wrap/Constructor.cpp b/wrap/Constructor.cpp index 782c0ca80..35cc0fa53 100644 --- a/wrap/Constructor.cpp +++ b/wrap/Constructor.cpp @@ -69,7 +69,7 @@ void Constructor::proxy_fragment(FileWriter& file, /* ************************************************************************* */ string Constructor::wrapper_fragment(FileWriter& file, Str cppClassName, - Str matlabUniqueName, Str cppBaseClassName, int id, + Str matlabUniqueName, boost::optional cppBaseClassName, int id, const ArgumentList& al) const { const string wrapFunctionName = matlabUniqueName + "_constructor_" @@ -100,9 +100,9 @@ string Constructor::wrapper_fragment(FileWriter& file, Str cppClassName, << endl; // If we have a base class, return the base class pointer (MATLAB will call the base class collectorInsertAndMakeBase to add this to the collector and recurse the heirarchy) - if (!cppBaseClassName.empty()) { + if (cppBaseClassName) { file.oss << "\n"; - file.oss << " typedef boost::shared_ptr<" << cppBaseClassName + file.oss << " typedef boost::shared_ptr<" << *cppBaseClassName << "> SharedBase;\n"; file.oss << " out[1] = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL);\n"; diff --git a/wrap/Constructor.h b/wrap/Constructor.h index a026bf423..1e061d17c 100644 --- a/wrap/Constructor.h +++ b/wrap/Constructor.h @@ -19,7 +19,7 @@ #pragma once #include "OverloadedFunction.h" - +#include #include #include @@ -68,7 +68,7 @@ struct Constructor: public OverloadedFunction { /// cpp wrapper std::string wrapper_fragment(FileWriter& file, Str cppClassName, - Str matlabUniqueName, Str cppBaseClassName, int id, + Str matlabUniqueName, boost::optional cppBaseClassName, int id, const ArgumentList& al) const; /// constructor function diff --git a/wrap/Function.cpp b/wrap/Function.cpp index d045d2915..babfd712f 100644 --- a/wrap/Function.cpp +++ b/wrap/Function.cpp @@ -29,8 +29,8 @@ using namespace std; using namespace wrap; /* ************************************************************************* */ -bool Function::initializeOrCheck(const string& name, const Qualified& instName, - bool verbose) { +bool Function::initializeOrCheck(const string& name, + boost::optional instName, bool verbose) { if (name.empty()) throw runtime_error("Function::initializeOrCheck called with empty name"); @@ -44,10 +44,7 @@ bool Function::initializeOrCheck(const string& name, const Qualified& instName, } else { if (name_ != name || templateArgValue_ != instName || verbose_ != verbose) throw runtime_error( - "Function::initializeOrCheck called with different arguments: with name " - + name + " instead of expected " + name_ - + ", or with template argument " + instName.qualifiedName(":") - + " instead of expected " + templateArgValue_.qualifiedName(":")); + "Function::initializeOrCheck called with different arguments"); return false; } diff --git a/wrap/Function.h b/wrap/Function.h index 249cd42a7..692b1dd76 100644 --- a/wrap/Function.h +++ b/wrap/Function.h @@ -19,6 +19,7 @@ #pragma once #include "Argument.h" +#include namespace wrap { @@ -28,7 +29,7 @@ class Function { protected: std::string name_; ///< name of method - Qualified templateArgValue_; ///< value of template argument if applicable + boost::optional templateArgValue_; ///< value of template argument if applicable bool verbose_; public: @@ -37,8 +38,8 @@ public: * @brief first time, fill in instance variables, otherwise check if same * @return true if first time, false thereafter */ - bool initializeOrCheck(const std::string& name, const Qualified& instName = - Qualified(), bool verbose = false); + bool initializeOrCheck(const std::string& name, boost::optional instName = + boost::none, bool verbose = false); std::string name() const { return name_; @@ -50,10 +51,10 @@ public: } std::string matlabName() const { - if (templateArgValue_.empty()) + if (templateArgValue_) return name_; else - return name_ + templateArgValue_.name; + return name_ + templateArgValue_->name; } /// Emit function call to MATLAB (no argument checking) diff --git a/wrap/Method.cpp b/wrap/Method.cpp index 66707d7e4..60d859ac3 100644 --- a/wrap/Method.cpp +++ b/wrap/Method.cpp @@ -52,8 +52,7 @@ void Method::proxy_header(FileWriter& proxyFile) const { /* ************************************************************************* */ string Method::wrapper_call(FileWriter& wrapperFile, Str cppClassName, - Str matlabUniqueName, const ArgumentList& args, - const Qualified& instName) const { + Str matlabUniqueName, const ArgumentList& args) const { // check arguments // extra argument obj -> nargin-1 is passed ! // example: checkArguments("equals",nargout,nargin-1,2); @@ -71,8 +70,8 @@ string Method::wrapper_call(FileWriter& wrapperFile, Str cppClassName, // call method and wrap result // example: out[0]=wrap(obj->return_field(t)); string expanded = "obj->" + name_; - if (!instName.empty()) - expanded += ("<" + instName.qualifiedName("::") + ">"); + if (templateArgValue_) + expanded += ("<" + templateArgValue_->qualifiedName("::") + ">"); return expanded; } diff --git a/wrap/Method.h b/wrap/Method.h index 160a0f454..5eea00c21 100644 --- a/wrap/Method.h +++ b/wrap/Method.h @@ -55,8 +55,7 @@ private: void proxy_header(FileWriter& proxyFile) const; virtual std::string wrapper_call(FileWriter& wrapperFile, Str cppClassName, - Str matlabUniqueName, const ArgumentList& args, - const Qualified& instName) const; + Str matlabUniqueName, const ArgumentList& args) const; }; } // \namespace wrap diff --git a/wrap/MethodBase.cpp b/wrap/MethodBase.cpp index 643d8ceec..6b3d345be 100644 --- a/wrap/MethodBase.cpp +++ b/wrap/MethodBase.cpp @@ -59,7 +59,7 @@ void MethodBase::proxy_wrapper_fragments(FileWriter& proxyFile, // Output C++ wrapper code const string wrapFunctionName = wrapper_fragment(wrapperFile, cppClassName, - matlabUniqueName, 0, id, typeAttributes, templateArgValue_); + matlabUniqueName, 0, id, typeAttributes); // Add to function list functionNames.push_back(wrapFunctionName); @@ -75,8 +75,7 @@ void MethodBase::proxy_wrapper_fragments(FileWriter& proxyFile, // Output C++ wrapper code const string wrapFunctionName = wrapper_fragment(wrapperFile, - cppClassName, matlabUniqueName, i, id, typeAttributes, - templateArgValue_); + cppClassName, matlabUniqueName, i, id, typeAttributes); // Add to function list functionNames.push_back(wrapFunctionName); @@ -94,8 +93,7 @@ void MethodBase::proxy_wrapper_fragments(FileWriter& proxyFile, /* ************************************************************************* */ string MethodBase::wrapper_fragment(FileWriter& wrapperFile, Str cppClassName, Str matlabUniqueName, int overload, int id, - const TypeAttributesTable& typeAttributes, - const Qualified& instName) const { + const TypeAttributesTable& typeAttributes) const { // generate code @@ -120,7 +118,7 @@ string MethodBase::wrapper_fragment(FileWriter& wrapperFile, Str cppClassName, // for static methods: cppClassName::staticMethod // for instance methods: obj->instanceMethod string expanded = wrapper_call(wrapperFile, cppClassName, matlabUniqueName, - args, instName); + args); expanded += ("(" + args.names() + ")"); if (returnVal.type1.name != "void") diff --git a/wrap/MethodBase.h b/wrap/MethodBase.h index 0aabe819d..903b89569 100644 --- a/wrap/MethodBase.h +++ b/wrap/MethodBase.h @@ -57,12 +57,10 @@ protected: std::string wrapper_fragment(FileWriter& wrapperFile, Str cppClassName, Str matlabUniqueName, int overload, int id, - const TypeAttributesTable& typeAttributes, const Qualified& instName = - Qualified()) const; ///< cpp wrapper + const TypeAttributesTable& typeAttributes) const; ///< cpp wrapper virtual std::string wrapper_call(FileWriter& wrapperFile, Str cppClassName, - Str matlabUniqueName, const ArgumentList& args, - const Qualified& instName) const = 0; + Str matlabUniqueName, const ArgumentList& args) const = 0; }; } // \namespace wrap diff --git a/wrap/Qualified.h b/wrap/Qualified.h index b23e9020d..3e2782a66 100644 --- a/wrap/Qualified.h +++ b/wrap/Qualified.h @@ -26,26 +26,53 @@ namespace wrap { /** * Class to encapuslate a qualified name, i.e., with (nested) namespaces */ -struct Qualified { +class Qualified { + +public: std::vector namespaces; ///< Stack of namespaces std::string name; ///< type name - Qualified(const std::string& name_ = "") : - name(name_) { + /// the different supported return value categories + typedef enum { + CLASS = 1, EIGEN = 2, BASIS = 3, VOID = 4 + } Category; + Category category_; + + Qualified() : + category_(CLASS) { } - bool empty() const { - return namespaces.empty() && name.empty(); + Qualified(std::vector ns, const std::string& name) : + namespaces(ns), name(name), category_(CLASS) { } - void clear() { - namespaces.clear(); - name.clear(); + Qualified(const std::string& n, Category category) : + name(n), category_(category) { + } + +public: + + static Qualified MakeClass(std::vector namespaces, + const std::string& name) { + return Qualified(namespaces, name); + } + + static Qualified MakeEigen(const std::string& name) { + return Qualified(name, EIGEN); + } + + static Qualified MakeBasis(const std::string& name) { + return Qualified(name, BASIS); + } + + static Qualified MakeVoid() { + return Qualified("void", VOID); } bool operator!=(const Qualified& other) const { - return other.name != name || other.namespaces != namespaces; + return other.name != name || other.namespaces != namespaces + || other.category_ != category_; } /// Return a qualified string using given delimiter diff --git a/wrap/ReturnType.cpp b/wrap/ReturnType.cpp index 25147e59a..2a925b819 100644 --- a/wrap/ReturnType.cpp +++ b/wrap/ReturnType.cpp @@ -23,7 +23,7 @@ void ReturnType::wrap_result(const string& out, const string& result, string cppType = qualifiedName("::"), matlabType = qualifiedName("."); - if (category == CLASS) { + if (category_ == CLASS) { string objCopy, ptrType; ptrType = "Shared" + name; const bool isVirtual = typeAttributes.attributes(cppType).isVirtual; @@ -52,7 +52,7 @@ void ReturnType::wrap_result(const string& out, const string& result, /* ************************************************************************* */ void ReturnType::wrapTypeUnwrap(FileWriter& wrapperFile) const { - if (category == CLASS) + if (category_ == CLASS) wrapperFile.oss << " typedef boost::shared_ptr<" << qualifiedName("::") << "> Shared" << name << ";" << endl; } diff --git a/wrap/ReturnType.h b/wrap/ReturnType.h index 1829fbc81..52d5c7ad5 100644 --- a/wrap/ReturnType.h +++ b/wrap/ReturnType.h @@ -17,22 +17,16 @@ namespace wrap { /** * Encapsulates return value of a method or function */ -struct ReturnType: Qualified { - - /// the different supported return value categories - typedef enum { - CLASS = 1, EIGEN = 2, BASIS = 3, VOID = 4 - } return_category; +struct ReturnType: public Qualified { bool isPtr; - return_category category; ReturnType() : - isPtr(false), category(CLASS) { + isPtr(false) { } ReturnType(const std::string& name) : - isPtr(false), category(CLASS) { + isPtr(false) { Qualified::name = name; } diff --git a/wrap/ReturnValue.cpp b/wrap/ReturnValue.cpp index 596acb2c3..dbf6277a7 100644 --- a/wrap/ReturnValue.cpp +++ b/wrap/ReturnValue.cpp @@ -64,7 +64,7 @@ void ReturnValue::emit_matlab(FileWriter& proxyFile) const { string output; if (isPair) proxyFile.oss << "[ varargout{1} varargout{2} ] = "; - else if (type1.category != ReturnType::VOID) + else if (type1.category_ != ReturnType::VOID) proxyFile.oss << "varargout{1} = "; } diff --git a/wrap/ReturnValue.h b/wrap/ReturnValue.h index abfcec2b0..e2af5ddbb 100644 --- a/wrap/ReturnValue.h +++ b/wrap/ReturnValue.h @@ -50,7 +50,7 @@ struct ReturnValue { void emit_matlab(FileWriter& proxyFile) const; friend std::ostream& operator<<(std::ostream& os, const ReturnValue& r) { - if (!r.isPair && r.type1.category == ReturnType::VOID) + if (!r.isPair && r.type1.category_ == ReturnType::VOID) os << "void"; else os << r.return_type(true); diff --git a/wrap/StaticMethod.cpp b/wrap/StaticMethod.cpp index 6a2917eb2..e4e7c89ae 100644 --- a/wrap/StaticMethod.cpp +++ b/wrap/StaticMethod.cpp @@ -38,8 +38,7 @@ void StaticMethod::proxy_header(FileWriter& proxyFile) const { /* ************************************************************************* */ string StaticMethod::wrapper_call(FileWriter& wrapperFile, Str cppClassName, - Str matlabUniqueName, const ArgumentList& args, - const Qualified& instName) const { + Str matlabUniqueName, const ArgumentList& args) const { // check arguments // NOTE: for static functions, there is no object passed wrapperFile.oss << " checkArguments(\"" << matlabUniqueName << "." << name_ @@ -51,8 +50,8 @@ string StaticMethod::wrapper_call(FileWriter& wrapperFile, Str cppClassName, // call method and wrap result // example: out[0]=wrap(staticMethod(t)); string expanded = cppClassName + "::" + name_; - if (!instName.empty()) - expanded += ("<" + instName.qualifiedName("::") + ">"); + if (templateArgValue_) + expanded += ("<" + templateArgValue_->qualifiedName("::") + ">"); return expanded; } diff --git a/wrap/StaticMethod.h b/wrap/StaticMethod.h index c3bf526dd..a01eeff62 100644 --- a/wrap/StaticMethod.h +++ b/wrap/StaticMethod.h @@ -39,8 +39,7 @@ protected: virtual void proxy_header(FileWriter& proxyFile) const; virtual std::string wrapper_call(FileWriter& wrapperFile, Str cppClassName, - Str matlabUniqueName, const ArgumentList& args, - const Qualified& instName) const; + Str matlabUniqueName, const ArgumentList& args) const; }; } // \namespace wrap diff --git a/wrap/TypeAttributesTable.cpp b/wrap/TypeAttributesTable.cpp index a836f2005..4252c097d 100644 --- a/wrap/TypeAttributesTable.cpp +++ b/wrap/TypeAttributesTable.cpp @@ -65,14 +65,14 @@ void TypeAttributesTable::addForwardDeclarations( void TypeAttributesTable::checkValidity(const vector& classes) const { BOOST_FOREACH(const Class& cls, classes) { // Check that class is virtual if it has a parent - if (!cls.qualifiedParent.empty() && !cls.isVirtual) + if (cls.parentClass && !cls.isVirtual) throw AttributeError(cls.qualifiedName("::"), "Has a base class so needs to be declared virtual, change to 'virtual class " + cls.name + " ...'"); // Check that parent is virtual as well - Qualified parent = cls.qualifiedParent; - if (!parent.empty() && !table_.at(parent.qualifiedName("::")).isVirtual) - throw AttributeError(parent.qualifiedName("::"), + if (cls.parentClass + && !table_.at(cls.parentClass->qualifiedName("::")).isVirtual) + throw AttributeError(cls.parentClass->qualifiedName("::"), "Is the base class of " + cls.qualifiedName("::") + ", so needs to be declared virtual"); } diff --git a/wrap/tests/testWrap.cpp b/wrap/tests/testWrap.cpp index c1f6f091e..b0c59addc 100644 --- a/wrap/tests/testWrap.cpp +++ b/wrap/tests/testWrap.cpp @@ -104,7 +104,7 @@ TEST( wrap, Small ) { EXPECT(!rv1.isPair); EXPECT(!rv1.type1.isPtr); EXPECT(assert_equal("double", rv1.type1.name)); - EXPECT_LONGS_EQUAL(ReturnType::BASIS, rv1.type1.category); + EXPECT_LONGS_EQUAL(ReturnType::BASIS, rv1.type1.category_); // Method 2 Method m2 = cls.method("returnMatrix"); @@ -116,7 +116,7 @@ TEST( wrap, Small ) { EXPECT(!rv2.isPair); EXPECT(!rv2.type1.isPtr); EXPECT(assert_equal("Matrix", rv2.type1.name)); - EXPECT_LONGS_EQUAL(ReturnType::EIGEN, rv2.type1.category); + EXPECT_LONGS_EQUAL(ReturnType::EIGEN, rv2.type1.category_); // Method 3 Method m3 = cls.method("returnPoint2"); @@ -128,7 +128,7 @@ TEST( wrap, Small ) { EXPECT(!rv3.isPair); EXPECT(!rv3.type1.isPtr); EXPECT(assert_equal("Point2", rv3.type1.name)); - EXPECT_LONGS_EQUAL(ReturnType::CLASS, rv3.type1.category); + EXPECT_LONGS_EQUAL(ReturnType::CLASS, rv3.type1.category_); // Static Method 1 // static Vector returnVector(); @@ -140,7 +140,7 @@ TEST( wrap, Small ) { EXPECT(!rv4.isPair); EXPECT(!rv4.type1.isPtr); EXPECT(assert_equal("Vector", rv4.type1.name)); - EXPECT_LONGS_EQUAL(ReturnType::EIGEN, rv4.type1.category); + EXPECT_LONGS_EQUAL(ReturnType::EIGEN, rv4.type1.category_); } @@ -192,7 +192,7 @@ TEST( wrap, Geometry ) { Method m1 = cls.method("returnChar"); LONGS_EQUAL(1, m1.nrOverloads()); EXPECT(assert_equal("char", m1.returnValue(0).type1.name)); - EXPECT_LONGS_EQUAL(ReturnType::BASIS, m1.returnValue(0).type1.category); + EXPECT_LONGS_EQUAL(ReturnType::BASIS, m1.returnValue(0).type1.category_); EXPECT(!m1.returnValue(0).isPair); EXPECT(assert_equal("returnChar", m1.name())); LONGS_EQUAL(1, m1.nrOverloads()); @@ -206,7 +206,7 @@ TEST( wrap, Geometry ) { Method m1 = cls.method("vectorConfusion"); LONGS_EQUAL(1, m1.nrOverloads()); EXPECT(assert_equal("VectorNotEigen", m1.returnValue(0).type1.name)); - EXPECT_LONGS_EQUAL(ReturnType::CLASS, m1.returnValue(0).type1.category); + EXPECT_LONGS_EQUAL(ReturnType::CLASS, m1.returnValue(0).type1.category_); EXPECT(!m1.returnValue(0).isPair); EXPECT(assert_equal("vectorConfusion", m1.name())); LONGS_EQUAL(1, m1.nrOverloads()); @@ -249,7 +249,7 @@ TEST( wrap, Geometry ) { Method m1 = cls.method("norm"); LONGS_EQUAL(1, m1.nrOverloads()); EXPECT(assert_equal("double", m1.returnValue(0).type1.name)); - EXPECT_LONGS_EQUAL(ReturnType::BASIS, m1.returnValue(0).type1.category); + EXPECT_LONGS_EQUAL(ReturnType::BASIS, m1.returnValue(0).type1.category_); EXPECT(assert_equal("norm", m1.name())); LONGS_EQUAL(1, m1.nrOverloads()); EXPECT_LONGS_EQUAL(0, m1.argumentList(0).size()); @@ -275,9 +275,9 @@ TEST( wrap, Geometry ) { Method m2 = testCls.method("return_pair"); LONGS_EQUAL(1, m2.nrOverloads()); EXPECT(m2.returnValue(0).isPair); - EXPECT_LONGS_EQUAL(ReturnType::EIGEN, m2.returnValue(0).type1.category); + EXPECT_LONGS_EQUAL(ReturnType::EIGEN, m2.returnValue(0).type1.category_); EXPECT(assert_equal("Vector", m2.returnValue(0).type1.name)); - EXPECT_LONGS_EQUAL(ReturnType::EIGEN, m2.returnValue(0).type2.category); + EXPECT_LONGS_EQUAL(ReturnType::EIGEN, m2.returnValue(0).type2.category_); EXPECT(assert_equal("Matrix", m2.returnValue(0).type2.name)); // checking pointer args and return values From c9ca9c82a0a2f5b3704d4ff2454c5ae0abaabe5c Mon Sep 17 00:00:00 2001 From: dellaert Date: Sun, 30 Nov 2014 10:51:32 +0100 Subject: [PATCH 033/126] GTSAM header that gets parsed correctly --- gtsam.h | 11 ++++------- 1 file changed, 4 insertions(+), 7 deletions(-) diff --git a/gtsam.h b/gtsam.h index b40913229..96d51117a 100644 --- a/gtsam.h +++ b/gtsam.h @@ -1739,7 +1739,7 @@ class Values { void insert(size_t j, const gtsam::EssentialMatrix& t); void insert(size_t j, const gtsam::imuBias::ConstantBias& t); void insert(size_t j, Vector t); - void insert(size_t j, Matrix t); //git/gtsam/gtsam/base/Manifold.h:254:1: error: invalid application of ‘sizeof’ to incomplete type ‘boost::STATIC_ASSERTION_FAILURE’ + void insert(size_t j, Matrix t); void update(size_t j, const gtsam::Point2& t); void update(size_t j, const gtsam::Point3& t); @@ -1755,8 +1755,7 @@ class Values { void update(size_t j, Vector t); void update(size_t j, Matrix t); - template // Parse Error + template T at(size_t j); }; @@ -2154,9 +2153,7 @@ class NonlinearISAM { #include #include -template // Parse Error +template virtual class PriorFactor : gtsam::NoiseModelFactor { PriorFactor(size_t key, const T& prior, const gtsam::noiseModel::Base* noiseModel); T prior() const; @@ -2167,7 +2164,7 @@ virtual class PriorFactor : gtsam::NoiseModelFactor { #include -template // Parse Error +template virtual class BetweenFactor : gtsam::NoiseModelFactor { BetweenFactor(size_t key1, size_t key2, const T& relativePose, const gtsam::noiseModel::Base* noiseModel); T measured() const; From e98ec628044d8e48a0df66a35fdceb4ec08de302 Mon Sep 17 00:00:00 2001 From: dellaert Date: Sun, 30 Nov 2014 11:09:34 +0100 Subject: [PATCH 034/126] start with grammar prototype --- .cproject | 106 ++++++++++++++++++++-------------------- wrap/tests/testType.cpp | 105 +++++++++++++++++++++++++++++++++++++++ 2 files changed, 157 insertions(+), 54 deletions(-) create mode 100644 wrap/tests/testType.cpp diff --git a/.cproject b/.cproject index 1dcc51dfe..c18177bf8 100644 --- a/.cproject +++ b/.cproject @@ -592,7 +592,6 @@ make - tests/testBayesTree.run true false @@ -600,7 +599,6 @@ make - testBinaryBayesNet.run true false @@ -648,7 +646,6 @@ make - testSymbolicBayesNet.run true false @@ -656,7 +653,6 @@ make - tests/testSymbolicFactor.run true false @@ -664,7 +660,6 @@ make - testSymbolicFactorGraph.run true false @@ -680,7 +675,6 @@ make - tests/testBayesTree true false @@ -1128,7 +1122,6 @@ make - testErrors.run true false @@ -1358,46 +1351,6 @@ true true - - make - -j5 - testBTree.run - true - true - true - - - make - -j5 - testDSF.run - true - true - true - - - make - -j5 - testDSFMap.run - true - true - true - - - make - -j5 - testDSFVector.run - true - true - true - - - make - -j5 - testFixedVector.run - true - true - true - make -j2 @@ -1480,6 +1433,7 @@ make + testSimulated2DOriented.run true false @@ -1519,6 +1473,7 @@ make + testSimulated2D.run true false @@ -1526,6 +1481,7 @@ make + testSimulated3D.run true false @@ -1539,6 +1495,46 @@ true true + + make + -j5 + testBTree.run + true + true + true + + + make + -j5 + testDSF.run + true + true + true + + + make + -j5 + testDSFMap.run + true + true + true + + + make + -j5 + testDSFVector.run + true + true + true + + + make + -j5 + testFixedVector.run + true + true + true + make -j5 @@ -1796,7 +1792,6 @@ cpack - -G DEB true false @@ -1804,7 +1799,6 @@ cpack - -G RPM true false @@ -1812,7 +1806,6 @@ cpack - -G TGZ true false @@ -1820,7 +1813,6 @@ cpack - --config CPackSourceConfig.cmake true false @@ -2401,6 +2393,14 @@ true true + + make + -j4 + testType.run + true + true + true + make -j5 @@ -2635,7 +2635,6 @@ make - testGraph.run true false @@ -2643,7 +2642,6 @@ make - testJunctionTree.run true false @@ -2651,7 +2649,6 @@ make - testSymbolicBayesNetB.run true false @@ -3187,6 +3184,7 @@ make + tests/testGaussianISAM2 true false diff --git a/wrap/tests/testType.cpp b/wrap/tests/testType.cpp new file mode 100644 index 000000000..59ccd279d --- /dev/null +++ b/wrap/tests/testType.cpp @@ -0,0 +1,105 @@ +/* ---------------------------------------------------------------------------- + + * GTSAM Copyright 2010, Georgia Tech Research Corporation, + * Atlanta, Georgia 30332-0415 + * All Rights Reserved + * Authors: Frank Dellaert, et al. (see THANKS for the full author list) + + * See LICENSE for the license information + + * -------------------------------------------------------------------------- */ + +/** + * @file testType.cpp + * @brief unit test for parsing a fully qualified type + * @author Frank Dellaert + * @date Nov 30, 2014 + **/ + +#include +#include + +#include +#include +#include + +using namespace std; +using namespace wrap; +using namespace BOOST_SPIRIT_CLASSIC_NS; + +typedef rule Rule; + +//****************************************************************************** +// http://boost-spirit.com/distrib/spirit_1_8_2/libs/spirit/doc/grammar.html +struct type_grammar: public grammar { + + Qualified& result_; ///< successful parse will be placed in here + + /// Construct type grammar and specify where result is placed + type_grammar(Qualified& result) : + result_(result) { + } + +/// Definition of type grammar + template + struct definition { + + typedef rule Rule; + + Rule basisType_p, keywords_p, eigenType_p, stlType_p, className_p, + namepsace_p, namespace_del_p, qualified_p, type_p; + + definition(type_grammar const& self) { + basisType_p = (str_p("string") | "bool" | "size_t" | "int" | "double" + | "char" | "unsigned char")[assign_a(self.result_.name)]; + + eigenType_p = (str_p("Vector") | "Matrix")[assign_a(self.result_.name)]; + + keywords_p = (str_p("const") | "static" | "namespace" | "void" + | basisType_p); + + //Rule for STL Containers (class names are lowercase) + stlType_p = (str_p("vector") | "list"); + + className_p = (lexeme_d[upper_p >> *(alnum_p | '_')] - eigenType_p + - keywords_p) | stlType_p; + + namepsace_p = lexeme_d[lower_p >> *(alnum_p | '_')] - keywords_p; + + namespace_del_p = namepsace_p[push_back_a(self.result_.namespaces)] + >> str_p("::"); + + qualified_p = *namespace_del_p + >> className_p[assign_a(self.result_.name)]; + + type_p = basisType_p | eigenType_p; + } + + Rule const& start() const { + return type_p; + } + + }; +}; + +//****************************************************************************** +TEST( spirit, grammar ) { + // Create grammar that will place result in actual + Qualified actual; + type_grammar type_g(actual); + + // a basic type + EXPECT(parse("double", type_g, space_p).full); + EXPECT(actual.name=="double"); + + // an Eigen type + EXPECT(parse("Vector", type_g, space_p).full); + EXPECT(actual.name=="Vector"); +} + +//****************************************************************************** +int main() { + TestResult tr; + return TestRegistry::runAllTests(tr); +} +//****************************************************************************** From f32f5c7ff2877b218d40e3a2b98fb00c40ba430c Mon Sep 17 00:00:00 2001 From: dellaert Date: Sun, 30 Nov 2014 11:19:23 +0100 Subject: [PATCH 035/126] Working type grammar --- wrap/tests/testType.cpp | 41 ++++++++++++++++++++++++++++++++--------- 1 file changed, 32 insertions(+), 9 deletions(-) diff --git a/wrap/tests/testType.cpp b/wrap/tests/testType.cpp index 59ccd279d..00b6f2f58 100644 --- a/wrap/tests/testType.cpp +++ b/wrap/tests/testType.cpp @@ -21,6 +21,8 @@ #include #include +#include +#include #include using namespace std; @@ -46,10 +48,13 @@ struct type_grammar: public grammar { typedef rule Rule; - Rule basisType_p, keywords_p, eigenType_p, stlType_p, className_p, - namepsace_p, namespace_del_p, qualified_p, type_p; + Rule void_p, basisType_p, eigenType_p, keywords_p, stlType_p, className_p, + namepsace_p, namespace_del_p, class_p, type_p; definition(type_grammar const& self) { + + void_p = str_p("void")[assign_a(self.result_.name)]; + basisType_p = (str_p("string") | "bool" | "size_t" | "int" | "double" | "char" | "unsigned char")[assign_a(self.result_.name)]; @@ -58,7 +63,6 @@ struct type_grammar: public grammar { keywords_p = (str_p("const") | "static" | "namespace" | "void" | basisType_p); - //Rule for STL Containers (class names are lowercase) stlType_p = (str_p("vector") | "list"); className_p = (lexeme_d[upper_p >> *(alnum_p | '_')] - eigenType_p @@ -69,10 +73,10 @@ struct type_grammar: public grammar { namespace_del_p = namepsace_p[push_back_a(self.result_.namespaces)] >> str_p("::"); - qualified_p = *namespace_del_p - >> className_p[assign_a(self.result_.name)]; + class_p = *namespace_del_p >> className_p[assign_a(self.result_.name)]; - type_p = basisType_p | eigenType_p; + type_p = eps_p[clear_a(self.result_)] // + >> void_p | basisType_p | eigenType_p | class_p; } Rule const& start() const { @@ -88,13 +92,32 @@ TEST( spirit, grammar ) { Qualified actual; type_grammar type_g(actual); - // a basic type - EXPECT(parse("double", type_g, space_p).full); - EXPECT(actual.name=="double"); + // a class type with namespaces + EXPECT(parse("gtsam::internal::Point2", type_g, space_p).full); + EXPECT(actual.name=="Point2"); + EXPECT_LONGS_EQUAL(2, actual.namespaces.size()); + EXPECT(actual.namespaces[0]=="gtsam"); + EXPECT(actual.namespaces[1]=="internal"); + + // a class type with no namespaces + EXPECT(parse("Point2", type_g, space_p).full); + EXPECT(actual.name=="Point2"); + EXPECT(actual.namespaces.empty()); // an Eigen type EXPECT(parse("Vector", type_g, space_p).full); EXPECT(actual.name=="Vector"); + EXPECT(actual.namespaces.empty()); + + // a basic type + EXPECT(parse("double", type_g, space_p).full); + EXPECT(actual.name=="double"); + EXPECT(actual.namespaces.empty()); + + // void + EXPECT(parse("void", type_g, space_p).full); + EXPECT(actual.name=="void"); + EXPECT(actual.namespaces.empty()); } //****************************************************************************** From ad8a25c78c1a6be7c2c940b95a460bb783dc4d5d Mon Sep 17 00:00:00 2001 From: dellaert Date: Sun, 30 Nov 2014 11:24:12 +0100 Subject: [PATCH 036/126] A bit of namespace shielding for use in header --- wrap/tests/testType.cpp | 21 +++++++++++++++++---- 1 file changed, 17 insertions(+), 4 deletions(-) diff --git a/wrap/tests/testType.cpp b/wrap/tests/testType.cpp index 00b6f2f58..7b3c8665d 100644 --- a/wrap/tests/testType.cpp +++ b/wrap/tests/testType.cpp @@ -27,13 +27,13 @@ using namespace std; using namespace wrap; -using namespace BOOST_SPIRIT_CLASSIC_NS; +namespace classic = BOOST_SPIRIT_CLASSIC_NS; -typedef rule Rule; +typedef classic::rule Rule; //****************************************************************************** // http://boost-spirit.com/distrib/spirit_1_8_2/libs/spirit/doc/grammar.html -struct type_grammar: public grammar { +struct type_grammar: public classic::grammar { Qualified& result_; ///< successful parse will be placed in here @@ -46,13 +46,23 @@ struct type_grammar: public grammar { template struct definition { - typedef rule Rule; + typedef classic::rule Rule; Rule void_p, basisType_p, eigenType_p, keywords_p, stlType_p, className_p, namepsace_p, namespace_del_p, class_p, type_p; definition(type_grammar const& self) { + using classic::lexeme_d; + using classic::eps_p; + using classic::str_p; + using classic::upper_p; + using classic::lower_p; + using classic::alnum_p; + using classic::assign_a; + using classic::push_back_a; + using classic::clear_a; + void_p = str_p("void")[assign_a(self.result_.name)]; basisType_p = (str_p("string") | "bool" | "size_t" | "int" | "double" @@ -88,6 +98,9 @@ struct type_grammar: public grammar { //****************************************************************************** TEST( spirit, grammar ) { + + using classic::space_p; + // Create grammar that will place result in actual Qualified actual; type_grammar type_g(actual); From 3f308e5f8693151299ea62488f059eb55e64f834 Mon Sep 17 00:00:00 2001 From: dellaert Date: Sun, 30 Nov 2014 11:30:06 +0100 Subject: [PATCH 037/126] Moved to header --- wrap/Qualified.h | 64 +++++++++++++++++++++++++++++++++++ wrap/tests/testType.cpp | 74 ----------------------------------------- 2 files changed, 64 insertions(+), 74 deletions(-) diff --git a/wrap/Qualified.h b/wrap/Qualified.h index b23e9020d..743b99b48 100644 --- a/wrap/Qualified.h +++ b/wrap/Qualified.h @@ -75,3 +75,67 @@ struct Qualified { } // \namespace wrap +#include +#include +#include +#include + +namespace classic = BOOST_SPIRIT_CLASSIC_NS; + +// http://boost-spirit.com/distrib/spirit_1_8_2/libs/spirit/doc/grammar.html +struct type_grammar: public classic::grammar { + + wrap::Qualified& result_; ///< successful parse will be placed in here + + /// Construct type grammar and specify where result is placed + type_grammar(wrap::Qualified& result) : + result_(result) { + } + +/// Definition of type grammar + template + struct definition { + + typedef classic::rule Rule; + + Rule void_p, basisType_p, eigenType_p, keywords_p, stlType_p, className_p, + namepsace_p, namespace_del_p, class_p, type_p; + + definition(type_grammar const& self) { + + using namespace classic; + + void_p = str_p("void")[assign_a(self.result_.name)]; + + basisType_p = (str_p("string") | "bool" | "size_t" | "int" | "double" + | "char" | "unsigned char")[assign_a(self.result_.name)]; + + eigenType_p = (str_p("Vector") | "Matrix")[assign_a(self.result_.name)]; + + keywords_p = (str_p("const") | "static" | "namespace" | "void" + | basisType_p); + + stlType_p = (str_p("vector") | "list"); + + className_p = (lexeme_d[upper_p >> *(alnum_p | '_')] - eigenType_p + - keywords_p) | stlType_p; + + namepsace_p = lexeme_d[lower_p >> *(alnum_p | '_')] - keywords_p; + + namespace_del_p = namepsace_p[push_back_a(self.result_.namespaces)] + >> str_p("::"); + + class_p = *namespace_del_p >> className_p[assign_a(self.result_.name)]; + + type_p = eps_p[clear_a(self.result_)] // + >> void_p | basisType_p | eigenType_p | class_p; + } + + Rule const& start() const { + return type_p; + } + + }; +}; + + diff --git a/wrap/tests/testType.cpp b/wrap/tests/testType.cpp index 7b3c8665d..9044f6aa2 100644 --- a/wrap/tests/testType.cpp +++ b/wrap/tests/testType.cpp @@ -17,84 +17,10 @@ **/ #include -#include - -#include -#include -#include -#include #include using namespace std; using namespace wrap; -namespace classic = BOOST_SPIRIT_CLASSIC_NS; - -typedef classic::rule Rule; - -//****************************************************************************** -// http://boost-spirit.com/distrib/spirit_1_8_2/libs/spirit/doc/grammar.html -struct type_grammar: public classic::grammar { - - Qualified& result_; ///< successful parse will be placed in here - - /// Construct type grammar and specify where result is placed - type_grammar(Qualified& result) : - result_(result) { - } - -/// Definition of type grammar - template - struct definition { - - typedef classic::rule Rule; - - Rule void_p, basisType_p, eigenType_p, keywords_p, stlType_p, className_p, - namepsace_p, namespace_del_p, class_p, type_p; - - definition(type_grammar const& self) { - - using classic::lexeme_d; - using classic::eps_p; - using classic::str_p; - using classic::upper_p; - using classic::lower_p; - using classic::alnum_p; - using classic::assign_a; - using classic::push_back_a; - using classic::clear_a; - - void_p = str_p("void")[assign_a(self.result_.name)]; - - basisType_p = (str_p("string") | "bool" | "size_t" | "int" | "double" - | "char" | "unsigned char")[assign_a(self.result_.name)]; - - eigenType_p = (str_p("Vector") | "Matrix")[assign_a(self.result_.name)]; - - keywords_p = (str_p("const") | "static" | "namespace" | "void" - | basisType_p); - - stlType_p = (str_p("vector") | "list"); - - className_p = (lexeme_d[upper_p >> *(alnum_p | '_')] - eigenType_p - - keywords_p) | stlType_p; - - namepsace_p = lexeme_d[lower_p >> *(alnum_p | '_')] - keywords_p; - - namespace_del_p = namepsace_p[push_back_a(self.result_.namespaces)] - >> str_p("::"); - - class_p = *namespace_del_p >> className_p[assign_a(self.result_.name)]; - - type_p = eps_p[clear_a(self.result_)] // - >> void_p | basisType_p | eigenType_p | class_p; - } - - Rule const& start() const { - return type_p; - } - - }; -}; //****************************************************************************** TEST( spirit, grammar ) { From ff3349c1e193b400a1c66cf6448517ad09df6305 Mon Sep 17 00:00:00 2001 From: dellaert Date: Sun, 30 Nov 2014 13:09:23 +0100 Subject: [PATCH 038/126] Moved category to Qualified --- wrap/Qualified.h | 113 ++++++++++++++++++++++++++++++++++------ wrap/ReturnType.h | 10 +--- wrap/tests/testType.cpp | 7 ++- 3 files changed, 104 insertions(+), 26 deletions(-) diff --git a/wrap/Qualified.h b/wrap/Qualified.h index 743b99b48..abc498de9 100644 --- a/wrap/Qualified.h +++ b/wrap/Qualified.h @@ -31,8 +31,14 @@ struct Qualified { std::vector namespaces; ///< Stack of namespaces std::string name; ///< type name + /// the different categories + typedef enum { + CLASS = 1, EIGEN = 2, BASIS = 3, VOID = 4 + } Category; + Category category; + Qualified(const std::string& name_ = "") : - name(name_) { + name(name_), category(CLASS) { } bool empty() const { @@ -82,35 +88,54 @@ struct Qualified { namespace classic = BOOST_SPIRIT_CLASSIC_NS; -// http://boost-spirit.com/distrib/spirit_1_8_2/libs/spirit/doc/grammar.html -struct type_grammar: public classic::grammar { +template +struct basic_rules { - wrap::Qualified& result_; ///< successful parse will be placed in here + typedef classic::rule Rule; - /// Construct type grammar and specify where result is placed - type_grammar(wrap::Qualified& result) : - result_(result) { + Rule basisType_p, eigenType_p, keywords_p, stlType_p, className_p, + namepsace_p; + + basic_rules() { + + using namespace classic; + + basisType_p = (str_p("string") | "bool" | "size_t" | "int" | "double" + | "char" | "unsigned char"); + + eigenType_p = (str_p("Vector") | "Matrix"); + + keywords_p = + (str_p("const") | "static" | "namespace" | "void" | basisType_p); + + stlType_p = (str_p("vector") | "list"); + + className_p = (lexeme_d[upper_p >> *(alnum_p | '_')] - eigenType_p + - keywords_p) | stlType_p; + + namepsace_p = lexeme_d[lower_p >> *(alnum_p | '_')] - keywords_p; } +}; -/// Definition of type grammar +// http://boost-spirit.com/distrib/spirit_1_8_2/libs/spirit/doc/grammar.html +struct classname_grammar: public classic::grammar { + + /// Definition of type grammar template struct definition { typedef classic::rule Rule; - Rule void_p, basisType_p, eigenType_p, keywords_p, stlType_p, className_p, - namepsace_p, namespace_del_p, class_p, type_p; + Rule basisType_p, eigenType_p, keywords_p, stlType_p, className_p; - definition(type_grammar const& self) { + definition(classname_grammar const& self) { using namespace classic; - void_p = str_p("void")[assign_a(self.result_.name)]; - basisType_p = (str_p("string") | "bool" | "size_t" | "int" | "double" - | "char" | "unsigned char")[assign_a(self.result_.name)]; + | "char" | "unsigned char"); - eigenType_p = (str_p("Vector") | "Matrix")[assign_a(self.result_.name)]; + eigenType_p = (str_p("Vector") | "Matrix"); keywords_p = (str_p("const") | "static" | "namespace" | "void" | basisType_p); @@ -119,13 +144,67 @@ struct type_grammar: public classic::grammar { className_p = (lexeme_d[upper_p >> *(alnum_p | '_')] - eigenType_p - keywords_p) | stlType_p; + } + + Rule const& start() const { + return className_p; + } + + }; +}; +// classname_grammar + +struct type_grammar: public classic::grammar { + + wrap::Qualified& result_; ///< successful parse will be placed in here + classname_grammar classname_g; + + /// Construct type grammar and specify where result is placed + type_grammar(wrap::Qualified& result) : + result_(result) { + } + + /// Definition of type grammar + template + struct definition { + + typedef classic::rule Rule; + + Rule void_p, basisType_p, eigenType_p, keywords_p, namepsace_p, + namespace_del_p, class_p, type_p; + + definition(type_grammar const& self) { + + using namespace wrap; + using namespace classic; + + // HACK: use const values instead of using enums themselves - somehow this doesn't result in values getting assigned to gibberish + static const Qualified::Category EIGEN = Qualified::EIGEN; + static const Qualified::Category BASIS = Qualified::BASIS; + static const Qualified::Category CLASS = Qualified::CLASS; + static const Qualified::Category VOID = Qualified::VOID; + + void_p = str_p("void")[assign_a(self.result_.name)] // + [assign_a(self.result_.category, VOID)]; + + basisType_p = (str_p("string") | "bool" | "size_t" | "int" | "double" + | "char" | "unsigned char")[assign_a(self.result_.name)] // + [assign_a(self.result_.category, BASIS)]; + + eigenType_p = (str_p("Vector") | "Matrix")[assign_a(self.result_.name)] // + [assign_a(self.result_.category, EIGEN)]; + + keywords_p = (str_p("const") | "static" | "namespace" | "void" + | basisType_p); namepsace_p = lexeme_d[lower_p >> *(alnum_p | '_')] - keywords_p; namespace_del_p = namepsace_p[push_back_a(self.result_.namespaces)] >> str_p("::"); - class_p = *namespace_del_p >> className_p[assign_a(self.result_.name)]; + class_p = *namespace_del_p >> self.classname_g // + [assign_a(self.result_.name)] // + [assign_a(self.result_.category, CLASS)]; type_p = eps_p[clear_a(self.result_)] // >> void_p | basisType_p | eigenType_p | class_p; @@ -137,5 +216,5 @@ struct type_grammar: public classic::grammar { }; }; - +// type_grammar diff --git a/wrap/ReturnType.h b/wrap/ReturnType.h index 1829fbc81..a56e31a24 100644 --- a/wrap/ReturnType.h +++ b/wrap/ReturnType.h @@ -19,20 +19,14 @@ namespace wrap { */ struct ReturnType: Qualified { - /// the different supported return value categories - typedef enum { - CLASS = 1, EIGEN = 2, BASIS = 3, VOID = 4 - } return_category; - bool isPtr; - return_category category; ReturnType() : - isPtr(false), category(CLASS) { + isPtr(false) { } ReturnType(const std::string& name) : - isPtr(false), category(CLASS) { + isPtr(false) { Qualified::name = name; } diff --git a/wrap/tests/testType.cpp b/wrap/tests/testType.cpp index 9044f6aa2..b7171f62c 100644 --- a/wrap/tests/testType.cpp +++ b/wrap/tests/testType.cpp @@ -27,7 +27,7 @@ TEST( spirit, grammar ) { using classic::space_p; - // Create grammar that will place result in actual + // Create type grammar that will place result in actual Qualified actual; type_grammar type_g(actual); @@ -37,26 +37,31 @@ TEST( spirit, grammar ) { EXPECT_LONGS_EQUAL(2, actual.namespaces.size()); EXPECT(actual.namespaces[0]=="gtsam"); EXPECT(actual.namespaces[1]=="internal"); + EXPECT(actual.category==Qualified::CLASS); // a class type with no namespaces EXPECT(parse("Point2", type_g, space_p).full); EXPECT(actual.name=="Point2"); EXPECT(actual.namespaces.empty()); + EXPECT(actual.category==Qualified::CLASS); // an Eigen type EXPECT(parse("Vector", type_g, space_p).full); EXPECT(actual.name=="Vector"); EXPECT(actual.namespaces.empty()); + EXPECT(actual.category==Qualified::EIGEN); // a basic type EXPECT(parse("double", type_g, space_p).full); EXPECT(actual.name=="double"); EXPECT(actual.namespaces.empty()); + EXPECT(actual.category==Qualified::BASIS); // void EXPECT(parse("void", type_g, space_p).full); EXPECT(actual.name=="void"); EXPECT(actual.namespaces.empty()); + EXPECT(actual.category==Qualified::VOID); } //****************************************************************************** From c9a15fbc387357ef678d15922e3efc8fb0af4012 Mon Sep 17 00:00:00 2001 From: dellaert Date: Sun, 30 Nov 2014 13:27:04 +0100 Subject: [PATCH 039/126] Now uses basic rules --- wrap/Qualified.h | 70 ++++++++++++++++-------------------------------- 1 file changed, 23 insertions(+), 47 deletions(-) diff --git a/wrap/Qualified.h b/wrap/Qualified.h index abc498de9..31a984f41 100644 --- a/wrap/Qualified.h +++ b/wrap/Qualified.h @@ -18,6 +18,13 @@ #pragma once +#include +#include +#include +#include + +namespace classic = BOOST_SPIRIT_CLASSIC_NS; + #include #include @@ -79,15 +86,6 @@ struct Qualified { }; -} // \namespace wrap - -#include -#include -#include -#include - -namespace classic = BOOST_SPIRIT_CLASSIC_NS; - template struct basic_rules { @@ -120,34 +118,14 @@ struct basic_rules { // http://boost-spirit.com/distrib/spirit_1_8_2/libs/spirit/doc/grammar.html struct classname_grammar: public classic::grammar { - /// Definition of type grammar template - struct definition { - - typedef classic::rule Rule; - - Rule basisType_p, eigenType_p, keywords_p, stlType_p, className_p; + struct definition: basic_rules { definition(classname_grammar const& self) { - - using namespace classic; - - basisType_p = (str_p("string") | "bool" | "size_t" | "int" | "double" - | "char" | "unsigned char"); - - eigenType_p = (str_p("Vector") | "Matrix"); - - keywords_p = (str_p("const") | "static" | "namespace" | "void" - | basisType_p); - - stlType_p = (str_p("vector") | "list"); - - className_p = (lexeme_d[upper_p >> *(alnum_p | '_')] - eigenType_p - - keywords_p) | stlType_p; } - Rule const& start() const { - return className_p; + classic::rule const& start() const { + return basic_rules::className_p; } }; @@ -166,12 +144,12 @@ struct type_grammar: public classic::grammar { /// Definition of type grammar template - struct definition { + struct definition: basic_rules { typedef classic::rule Rule; - Rule void_p, basisType_p, eigenType_p, keywords_p, namepsace_p, - namespace_del_p, class_p, type_p; + Rule void_p, my_basisType_p, my_eigenType_p, namespace_del_p, class_p, + type_p; definition(type_grammar const& self) { @@ -187,27 +165,23 @@ struct type_grammar: public classic::grammar { void_p = str_p("void")[assign_a(self.result_.name)] // [assign_a(self.result_.category, VOID)]; - basisType_p = (str_p("string") | "bool" | "size_t" | "int" | "double" - | "char" | "unsigned char")[assign_a(self.result_.name)] // + my_basisType_p = basic_rules::basisType_p // + [assign_a(self.result_.name)] // [assign_a(self.result_.category, BASIS)]; - eigenType_p = (str_p("Vector") | "Matrix")[assign_a(self.result_.name)] // + my_eigenType_p = basic_rules::eigenType_p // + [assign_a(self.result_.name)] // [assign_a(self.result_.category, EIGEN)]; - keywords_p = (str_p("const") | "static" | "namespace" | "void" - | basisType_p); + namespace_del_p = basic_rules::namepsace_p // + [push_back_a(self.result_.namespaces)] >> str_p("::"); - namepsace_p = lexeme_d[lower_p >> *(alnum_p | '_')] - keywords_p; - - namespace_del_p = namepsace_p[push_back_a(self.result_.namespaces)] - >> str_p("::"); - - class_p = *namespace_del_p >> self.classname_g // + class_p = *namespace_del_p >> basic_rules::className_p // [assign_a(self.result_.name)] // [assign_a(self.result_.category, CLASS)]; type_p = eps_p[clear_a(self.result_)] // - >> void_p | basisType_p | eigenType_p | class_p; + >> void_p | my_basisType_p | my_eigenType_p | class_p; } Rule const& start() const { @@ -218,3 +192,5 @@ struct type_grammar: public classic::grammar { }; // type_grammar +} // \namespace wrap + From 46ad6ea2e7d9d75bf2780815b60e142b25f6b60c Mon Sep 17 00:00:00 2001 From: dellaert Date: Sun, 30 Nov 2014 13:29:34 +0100 Subject: [PATCH 040/126] Got rid of that classname grammar --- wrap/Qualified.h | 17 ----------------- 1 file changed, 17 deletions(-) diff --git a/wrap/Qualified.h b/wrap/Qualified.h index 31a984f41..5825be619 100644 --- a/wrap/Qualified.h +++ b/wrap/Qualified.h @@ -116,26 +116,9 @@ struct basic_rules { }; // http://boost-spirit.com/distrib/spirit_1_8_2/libs/spirit/doc/grammar.html -struct classname_grammar: public classic::grammar { - - template - struct definition: basic_rules { - - definition(classname_grammar const& self) { - } - - classic::rule const& start() const { - return basic_rules::className_p; - } - - }; -}; -// classname_grammar - struct type_grammar: public classic::grammar { wrap::Qualified& result_; ///< successful parse will be placed in here - classname_grammar classname_g; /// Construct type grammar and specify where result is placed type_grammar(wrap::Qualified& result) : From 00c6bd24265c85a75582cdd6949a05605100d44d Mon Sep 17 00:00:00 2001 From: dellaert Date: Sun, 30 Nov 2014 14:58:45 +0100 Subject: [PATCH 041/126] Start on Argument grammar --- wrap/tests/testArgument.cpp | 187 ++++++++++++++++++++++++++++++++++++ 1 file changed, 187 insertions(+) create mode 100644 wrap/tests/testArgument.cpp diff --git a/wrap/tests/testArgument.cpp b/wrap/tests/testArgument.cpp new file mode 100644 index 000000000..d009ea0ba --- /dev/null +++ b/wrap/tests/testArgument.cpp @@ -0,0 +1,187 @@ +/* ---------------------------------------------------------------------------- + + * GTSAM Copyright 2010, Georgia Tech Research Corporation, + * Atlanta, Georgia 30332-0415 + * All Rights Reserved + * Authors: Frank Dellaert, et al. (see THANKS for the full author list) + + * See LICENSE for the license information + + * -------------------------------------------------------------------------- */ + +/** + * @file testArgument.cpp + * @brief Unit test for Argument class + * @author Frank Dellaert + * @date Nov 12, 2014 + **/ + +#include +#include +#include + +using namespace std; +using namespace wrap; + +/* ************************************************************************* */ +// http://boost-spirit.com/distrib/spirit_1_8_2/libs/spirit/doc/grammar.html +struct ArgumentGrammar: public classic::grammar { + + wrap::Argument& result_; ///< successful parse will be placed in here + type_grammar argument_type_g; + Argument arg0; + + /// Construct type grammar and specify where result is placed + ArgumentGrammar(wrap::Argument& result) : + result_(result), argument_type_g(result.type) { + } + + /// Definition of type grammar + template + struct definition: basic_rules { + + typedef classic::rule Rule; + + Rule argument_p, argumentList_p; + + definition(ArgumentGrammar const& self) { + + using namespace wrap; + using namespace classic; + + // NOTE: allows for pointers to all types + // Slightly more permissive than before on basis/eigen type qualification + argument_p = // + !str_p("const") +// [assign_a(self.arg.is_const, true)] // + >> self.argument_type_g // + >> (!ch_p('&') +// [assign_a(self.arg.is_ref, true)] + | !ch_p('*') +// [assign_a(self.arg.is_ptr, true)] + ) >> basic_rules::name_p + // [assign_a[self.arg.name)] +// [push_back_a(self.result_, self.arg)] + // [assign_a(self.arg, self.arg0)] + ; + } + + Rule const& start() const { + return argument_p; + } + + }; +}; +// ArgumentGrammar + +//****************************************************************************** +TEST( Argument, grammar ) { + + using classic::space_p; + + // Create type grammar that will place result in actual + Argument actual; + ArgumentGrammar g(actual); + + EXPECT(parse("const gtsam::Point2& p4", g, space_p).full); + + EXPECT(parse("Point2 p", g, space_p).full); + + EXPECT(parse("gtsam::Point2 p3", g, space_p).full); + + EXPECT(parse("char a", g, space_p).full); + + EXPECT(parse("unsigned char a", g, space_p).full); + + EXPECT(parse("Vector v", g, space_p).full); + + EXPECT(parse("Matrix m", g, space_p).full); + +} + +/* ************************************************************************* */ +// http://boost-spirit.com/distrib/spirit_1_8_2/libs/spirit/doc/grammar.html +struct ArgumentListGrammar: public classic::grammar { + + wrap::ArgumentList& result_; ///< successful parse will be placed in here + + Argument arg0, arg; + type_grammar argument_type_g; + + /// Construct type grammar and specify where result is placed + ArgumentListGrammar(wrap::ArgumentList& result) : + result_(result), argument_type_g(arg.type) { + } + + /// Definition of type grammar + template + struct definition: basic_rules { + + typedef classic::rule Rule; + + Rule argument_p, argumentList_p; + + definition(ArgumentListGrammar const& self) { + + using namespace wrap; + using namespace classic; + + // NOTE: allows for pointers to all types + // Slightly more permissive than before on basis/eigen type qualification + argument_p = // + !str_p("const") +// [assign_a(self.arg.is_const, true)] // + >> self.argument_type_g // + >> (!ch_p('&') +// [assign_a(self.arg.is_ref, true)] + | !ch_p('*') +// [assign_a(self.arg.is_ptr, true)] + ) >> basic_rules::name_p + // [assign_a[self.arg.name)] +// [push_back_a(self.result_, self.arg)] + // [assign_a(self.arg, self.arg0)] + ; + + argumentList_p = '(' >> !argument_p >> *(',' >> argument_p) >> ')'; + } + + Rule const& start() const { + return argumentList_p; + } + + }; +}; +// ArgumentListGrammar + +//****************************************************************************** +TEST( ArgumentList, grammar ) { + + using classic::space_p; + + // Create type grammar that will place result in actual + ArgumentList actual; + ArgumentListGrammar g(actual); + + EXPECT(parse("()", g, space_p).full); + + EXPECT(parse("(char a)", g, space_p).full); + + EXPECT(parse("(unsigned char a)", g, space_p).full); + + EXPECT(parse("(Vector v, Matrix m)", g, space_p).full); + + EXPECT(parse("(Point2 p)", g, space_p).full); + + EXPECT(parse("(Point2 p1, Point3 p2)", g, space_p).full); + + EXPECT(parse("(gtsam::Point2 p3)", g, space_p).full); + + EXPECT(parse("(const gtsam::Point2& p4)", g, space_p).full); +} + +/* ************************************************************************* */ +int main() { + TestResult tr; + return TestRegistry::runAllTests(tr); +} +/* ************************************************************************* */ From a6afe70c9c882791f81e297219f4fa2604941f2c Mon Sep 17 00:00:00 2001 From: dellaert Date: Sun, 30 Nov 2014 15:46:41 +0100 Subject: [PATCH 042/126] Good progress on Argument --- wrap/tests/testArgument.cpp | 77 +++++++++++++++++++++++++++++-------- 1 file changed, 60 insertions(+), 17 deletions(-) diff --git a/wrap/tests/testArgument.cpp b/wrap/tests/testArgument.cpp index d009ea0ba..c1d1cc72c 100644 --- a/wrap/tests/testArgument.cpp +++ b/wrap/tests/testArgument.cpp @@ -23,13 +23,14 @@ using namespace std; using namespace wrap; +static const bool T = true; + /* ************************************************************************* */ // http://boost-spirit.com/distrib/spirit_1_8_2/libs/spirit/doc/grammar.html struct ArgumentGrammar: public classic::grammar { wrap::Argument& result_; ///< successful parse will be placed in here type_grammar argument_type_g; - Argument arg0; /// Construct type grammar and specify where result is placed ArgumentGrammar(wrap::Argument& result) : @@ -51,19 +52,11 @@ struct ArgumentGrammar: public classic::grammar { // NOTE: allows for pointers to all types // Slightly more permissive than before on basis/eigen type qualification - argument_p = // - !str_p("const") -// [assign_a(self.arg.is_const, true)] // - >> self.argument_type_g // - >> (!ch_p('&') -// [assign_a(self.arg.is_ref, true)] - | !ch_p('*') -// [assign_a(self.arg.is_ptr, true)] - ) >> basic_rules::name_p - // [assign_a[self.arg.name)] -// [push_back_a(self.result_, self.arg)] - // [assign_a(self.arg, self.arg0)] - ; + argument_p = !str_p("const")[assign_a(self.result_.is_const, T)] // + >> self.argument_type_g // + >> (!ch_p('&')[assign_a(self.result_.is_ref, T)] + | !ch_p('*')[assign_a(self.result_.is_ptr, T)]) + >> basic_rules::name_p[assign_a(self.result_.name)]; } Rule const& start() const { @@ -80,23 +73,73 @@ TEST( Argument, grammar ) { using classic::space_p; // Create type grammar that will place result in actual - Argument actual; + Argument actual, arg0; ArgumentGrammar g(actual); EXPECT(parse("const gtsam::Point2& p4", g, space_p).full); + EXPECT_LONGS_EQUAL(1, actual.type.namespaces.size()); + EXPECT(actual.type.namespaces[0]=="gtsam"); + EXPECT(actual.type.name=="Point2"); + EXPECT(actual.name=="p4"); + EXPECT(actual.is_const); + EXPECT(actual.is_ref); + EXPECT(!actual.is_ptr); + actual = arg0; EXPECT(parse("Point2 p", g, space_p).full); + EXPECT(actual.type.namespaces.empty()); + EXPECT(actual.type.name=="Point2"); + EXPECT(actual.name=="p"); + EXPECT(!actual.is_const); + EXPECT(!actual.is_ref); + EXPECT(!actual.is_ptr); + actual = arg0; EXPECT(parse("gtsam::Point2 p3", g, space_p).full); + EXPECT_LONGS_EQUAL(1, actual.type.namespaces.size()); + EXPECT(actual.type.namespaces[0]=="gtsam"); + EXPECT(actual.type.name=="Point2"); + EXPECT(actual.name=="p3"); + EXPECT(!actual.is_const); + EXPECT(!actual.is_ref); + EXPECT(!actual.is_ptr); + actual = arg0; EXPECT(parse("char a", g, space_p).full); + EXPECT(actual.type.namespaces.empty()); + EXPECT(actual.type.name=="char"); + EXPECT(actual.name=="a"); + EXPECT(!actual.is_const); + EXPECT(!actual.is_ref); + EXPECT(!actual.is_ptr); + actual = arg0; EXPECT(parse("unsigned char a", g, space_p).full); + EXPECT(actual.type.namespaces.empty()); + EXPECT(actual.type.name=="unsigned char"); + EXPECT(actual.name=="a"); + EXPECT(!actual.is_const); + EXPECT(!actual.is_ref); + EXPECT(!actual.is_ptr); + actual = arg0; EXPECT(parse("Vector v", g, space_p).full); + EXPECT(actual.type.namespaces.empty()); + EXPECT(actual.type.name=="Vector"); + EXPECT(actual.name=="v"); + EXPECT(!actual.is_const); + EXPECT(!actual.is_ref); + EXPECT(!actual.is_ptr); + actual = arg0; - EXPECT(parse("Matrix m", g, space_p).full); - + EXPECT(parse("const Matrix& m", g, space_p).full); + EXPECT(actual.type.namespaces.empty()); + EXPECT(actual.type.name=="Matrix"); + EXPECT(actual.name=="m"); + EXPECT(actual.is_const); + EXPECT(actual.is_ref); + EXPECT(!actual.is_ptr); + actual = arg0; } /* ************************************************************************* */ From 8a54e198119c8d263052eb10be9692ef2e61ae52 Mon Sep 17 00:00:00 2001 From: dellaert Date: Sun, 30 Nov 2014 15:51:14 +0100 Subject: [PATCH 043/126] Succuessfully parse * at cost of also parsing *& --- wrap/tests/testArgument.cpp | 13 +++++++------ 1 file changed, 7 insertions(+), 6 deletions(-) diff --git a/wrap/tests/testArgument.cpp b/wrap/tests/testArgument.cpp index c1d1cc72c..f977bf3dc 100644 --- a/wrap/tests/testArgument.cpp +++ b/wrap/tests/testArgument.cpp @@ -52,10 +52,11 @@ struct ArgumentGrammar: public classic::grammar { // NOTE: allows for pointers to all types // Slightly more permissive than before on basis/eigen type qualification + // Also, currently parses Point2*&, can't make it work otherwise :-( argument_p = !str_p("const")[assign_a(self.result_.is_const, T)] // >> self.argument_type_g // - >> (!ch_p('&')[assign_a(self.result_.is_ref, T)] - | !ch_p('*')[assign_a(self.result_.is_ptr, T)]) + >> !ch_p('*')[assign_a(self.result_.is_ptr, T)] + >> !ch_p('&')[assign_a(self.result_.is_ref, T)] >> basic_rules::name_p[assign_a(self.result_.name)]; } @@ -86,23 +87,23 @@ TEST( Argument, grammar ) { EXPECT(!actual.is_ptr); actual = arg0; - EXPECT(parse("Point2 p", g, space_p).full); + EXPECT(parse("Point2& p", g, space_p).full); EXPECT(actual.type.namespaces.empty()); EXPECT(actual.type.name=="Point2"); EXPECT(actual.name=="p"); EXPECT(!actual.is_const); - EXPECT(!actual.is_ref); + EXPECT(actual.is_ref); EXPECT(!actual.is_ptr); actual = arg0; - EXPECT(parse("gtsam::Point2 p3", g, space_p).full); + EXPECT(parse("gtsam::Point2* p3", g, space_p).full); EXPECT_LONGS_EQUAL(1, actual.type.namespaces.size()); EXPECT(actual.type.namespaces[0]=="gtsam"); EXPECT(actual.type.name=="Point2"); EXPECT(actual.name=="p3"); EXPECT(!actual.is_const); EXPECT(!actual.is_ref); - EXPECT(!actual.is_ptr); + EXPECT(actual.is_ptr); actual = arg0; EXPECT(parse("char a", g, space_p).full); From e8c9b8c1d7817ccb4232791199cf5686b439eaa8 Mon Sep 17 00:00:00 2001 From: dellaert Date: Sun, 30 Nov 2014 16:08:08 +0100 Subject: [PATCH 044/126] Better message --- wrap/utilities.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/wrap/utilities.h b/wrap/utilities.h index a4f71b6ad..fbc8dc7a2 100644 --- a/wrap/utilities.h +++ b/wrap/utilities.h @@ -67,7 +67,7 @@ private: const std::string what_; public: DependencyMissing(const std::string& dep, const std::string& loc) : - what_("Missing dependency " + dep + " in " + loc) {} + what_("Missing dependency '" + dep + "' in " + loc) {} ~DependencyMissing() throw() {} virtual const char* what() const throw() { return what_.c_str(); } }; From 49f7f5c7fe5b06e6bea26928741ca51083aef198 Mon Sep 17 00:00:00 2001 From: dellaert Date: Sun, 30 Nov 2014 16:08:18 +0100 Subject: [PATCH 045/126] target --- .cproject | 8 ++++++++ 1 file changed, 8 insertions(+) diff --git a/.cproject b/.cproject index c18177bf8..cbe6f0b56 100644 --- a/.cproject +++ b/.cproject @@ -2401,6 +2401,14 @@ true true + + make + -j4 + testArgument.run + true + true + true + make -j5 From b50f42a6069017de95a2f0336e1a9c99c8976f34 Mon Sep 17 00:00:00 2001 From: dellaert Date: Sun, 30 Nov 2014 16:08:42 +0100 Subject: [PATCH 046/126] Equality --- wrap/Argument.h | 12 ++++++++- wrap/Qualified.h | 27 ++++++++++++++------ wrap/tests/testArgument.cpp | 50 +++++++++++-------------------------- 3 files changed, 46 insertions(+), 43 deletions(-) diff --git a/wrap/Argument.h b/wrap/Argument.h index 200269cc3..2a3e4b18b 100644 --- a/wrap/Argument.h +++ b/wrap/Argument.h @@ -28,13 +28,23 @@ namespace wrap { /// Argument class struct Argument { Qualified type; - bool is_const, is_ref, is_ptr; std::string name; + bool is_const, is_ref, is_ptr; Argument() : is_const(false), is_ref(false), is_ptr(false) { } + Argument(const Qualified& t, const std::string& n) : + type(t), name(n), is_const(false), is_ref(false), is_ptr(false) { + } + + bool operator==(const Argument& other) const { + return type == other.type && name == other.name + && is_const == other.is_const && is_ref == other.is_ref + && is_ptr == other.is_ptr; + } + Argument expandTemplate(const TemplateSubstitution& ts) const; /// return MATLAB class for use in isa(x,class) diff --git a/wrap/Qualified.h b/wrap/Qualified.h index 5825be619..1468c8d17 100644 --- a/wrap/Qualified.h +++ b/wrap/Qualified.h @@ -22,6 +22,7 @@ #include #include #include +#include namespace classic = BOOST_SPIRIT_CLASSIC_NS; @@ -44,8 +45,17 @@ struct Qualified { } Category; Category category; - Qualified(const std::string& name_ = "") : - name(name_), category(CLASS) { + Qualified() : + category(VOID) { + } + + Qualified(const std::string& name_, Category c = CLASS) : + name(name_), category(c) { + } + + bool operator==(const Qualified& other) const { + return namespaces == other.namespaces && name == other.name + && category == other.category; } bool empty() const { @@ -91,13 +101,15 @@ struct basic_rules { typedef classic::rule Rule; - Rule basisType_p, eigenType_p, keywords_p, stlType_p, className_p, - namepsace_p; + Rule comments_p, basisType_p, eigenType_p, keywords_p, stlType_p, name_p, + className_p, namepsace_p; basic_rules() { using namespace classic; + comments_p = comment_p("/*", "*/") | comment_p("//", eol_p); + basisType_p = (str_p("string") | "bool" | "size_t" | "int" | "double" | "char" | "unsigned char"); @@ -108,6 +120,8 @@ struct basic_rules { stlType_p = (str_p("vector") | "list"); + name_p = lexeme_d[alpha_p >> *(alnum_p | '_')]; + className_p = (lexeme_d[upper_p >> *(alnum_p | '_')] - eigenType_p - keywords_p) | stlType_p; @@ -163,8 +177,7 @@ struct type_grammar: public classic::grammar { [assign_a(self.result_.name)] // [assign_a(self.result_.category, CLASS)]; - type_p = eps_p[clear_a(self.result_)] // - >> void_p | my_basisType_p | my_eigenType_p | class_p; + type_p = void_p | my_basisType_p | my_eigenType_p | class_p; } Rule const& start() const { @@ -175,5 +188,5 @@ struct type_grammar: public classic::grammar { }; // type_grammar -} // \namespace wrap +}// \namespace wrap diff --git a/wrap/tests/testArgument.cpp b/wrap/tests/testArgument.cpp index f977bf3dc..418923f23 100644 --- a/wrap/tests/testArgument.cpp +++ b/wrap/tests/testArgument.cpp @@ -107,30 +107,15 @@ TEST( Argument, grammar ) { actual = arg0; EXPECT(parse("char a", g, space_p).full); - EXPECT(actual.type.namespaces.empty()); - EXPECT(actual.type.name=="char"); - EXPECT(actual.name=="a"); - EXPECT(!actual.is_const); - EXPECT(!actual.is_ref); - EXPECT(!actual.is_ptr); + EXPECT(actual==Argument(Qualified("char",Qualified::BASIS),"a")); actual = arg0; EXPECT(parse("unsigned char a", g, space_p).full); - EXPECT(actual.type.namespaces.empty()); - EXPECT(actual.type.name=="unsigned char"); - EXPECT(actual.name=="a"); - EXPECT(!actual.is_const); - EXPECT(!actual.is_ref); - EXPECT(!actual.is_ptr); + EXPECT(actual==Argument(Qualified("unsigned char",Qualified::BASIS),"a")); actual = arg0; EXPECT(parse("Vector v", g, space_p).full); - EXPECT(actual.type.namespaces.empty()); - EXPECT(actual.type.name=="Vector"); - EXPECT(actual.name=="v"); - EXPECT(!actual.is_const); - EXPECT(!actual.is_ref); - EXPECT(!actual.is_ptr); + EXPECT(actual==Argument(Qualified("Vector",Qualified::EIGEN),"v")); actual = arg0; EXPECT(parse("const Matrix& m", g, space_p).full); @@ -150,11 +135,11 @@ struct ArgumentListGrammar: public classic::grammar { wrap::ArgumentList& result_; ///< successful parse will be placed in here Argument arg0, arg; - type_grammar argument_type_g; + ArgumentGrammar argument_g; /// Construct type grammar and specify where result is placed ArgumentListGrammar(wrap::ArgumentList& result) : - result_(result), argument_type_g(arg.type) { + result_(result), argument_g(arg) { } /// Definition of type grammar @@ -172,19 +157,10 @@ struct ArgumentListGrammar: public classic::grammar { // NOTE: allows for pointers to all types // Slightly more permissive than before on basis/eigen type qualification - argument_p = // - !str_p("const") -// [assign_a(self.arg.is_const, true)] // - >> self.argument_type_g // - >> (!ch_p('&') -// [assign_a(self.arg.is_ref, true)] - | !ch_p('*') -// [assign_a(self.arg.is_ptr, true)] - ) >> basic_rules::name_p - // [assign_a[self.arg.name)] -// [push_back_a(self.result_, self.arg)] - // [assign_a(self.arg, self.arg0)] - ; + argument_p = self.argument_g // + [push_back_a(self.result_, self.arg)] // +// [assign_a(self.arg, self.arg0)] + ; argumentList_p = '(' >> !argument_p >> *(',' >> argument_p) >> ')'; } @@ -206,7 +182,13 @@ TEST( ArgumentList, grammar ) { ArgumentList actual; ArgumentListGrammar g(actual); + EXPECT(parse("(const gtsam::Point2& p4)", g, space_p).full); + EXPECT_LONGS_EQUAL(1, actual.size()); + actual.clear(); + EXPECT(parse("()", g, space_p).full); + EXPECT_LONGS_EQUAL(0, actual.size()); + actual.clear(); EXPECT(parse("(char a)", g, space_p).full); @@ -219,8 +201,6 @@ TEST( ArgumentList, grammar ) { EXPECT(parse("(Point2 p1, Point3 p2)", g, space_p).full); EXPECT(parse("(gtsam::Point2 p3)", g, space_p).full); - - EXPECT(parse("(const gtsam::Point2& p4)", g, space_p).full); } /* ************************************************************************* */ From f1c91d5d4ba1a01631c5c1abf1ff47494795f5e8 Mon Sep 17 00:00:00 2001 From: dellaert Date: Sun, 30 Nov 2014 16:09:13 +0100 Subject: [PATCH 047/126] Clear now up to caller --- wrap/tests/testType.cpp | 17 +++++++++++++++-- 1 file changed, 15 insertions(+), 2 deletions(-) diff --git a/wrap/tests/testType.cpp b/wrap/tests/testType.cpp index b7171f62c..538bcef3e 100644 --- a/wrap/tests/testType.cpp +++ b/wrap/tests/testType.cpp @@ -23,7 +23,7 @@ using namespace std; using namespace wrap; //****************************************************************************** -TEST( spirit, grammar ) { +TEST( Type, grammar ) { using classic::space_p; @@ -31,37 +31,50 @@ TEST( spirit, grammar ) { Qualified actual; type_grammar type_g(actual); - // a class type with namespaces + // a class type with 2 namespaces EXPECT(parse("gtsam::internal::Point2", type_g, space_p).full); EXPECT(actual.name=="Point2"); EXPECT_LONGS_EQUAL(2, actual.namespaces.size()); EXPECT(actual.namespaces[0]=="gtsam"); EXPECT(actual.namespaces[1]=="internal"); EXPECT(actual.category==Qualified::CLASS); + actual.clear(); + + // a class type with 1 namespace + EXPECT(parse("gtsam::Point2", type_g, space_p).full); + EXPECT(actual.name=="Point2"); + EXPECT_LONGS_EQUAL(1, actual.namespaces.size()); + EXPECT(actual.namespaces[0]=="gtsam"); + EXPECT(actual.category==Qualified::CLASS); + actual.clear(); // a class type with no namespaces EXPECT(parse("Point2", type_g, space_p).full); EXPECT(actual.name=="Point2"); EXPECT(actual.namespaces.empty()); EXPECT(actual.category==Qualified::CLASS); + actual.clear(); // an Eigen type EXPECT(parse("Vector", type_g, space_p).full); EXPECT(actual.name=="Vector"); EXPECT(actual.namespaces.empty()); EXPECT(actual.category==Qualified::EIGEN); + actual.clear(); // a basic type EXPECT(parse("double", type_g, space_p).full); EXPECT(actual.name=="double"); EXPECT(actual.namespaces.empty()); EXPECT(actual.category==Qualified::BASIS); + actual.clear(); // void EXPECT(parse("void", type_g, space_p).full); EXPECT(actual.name=="void"); EXPECT(actual.namespaces.empty()); EXPECT(actual.category==Qualified::VOID); + actual.clear(); } //****************************************************************************** From 6d916c6b754928454e1231eeaa155bc53b2f9b69 Mon Sep 17 00:00:00 2001 From: dellaert Date: Sun, 30 Nov 2014 20:12:03 +0100 Subject: [PATCH 048/126] Semi-private name/namespaces --- wrap/Argument.cpp | 30 ++-- wrap/Class.cpp | 36 ++-- wrap/Class.h | 2 +- wrap/Function.cpp | 2 +- wrap/Function.h | 2 +- wrap/GlobalFunction.cpp | 10 +- wrap/MethodBase.cpp | 2 +- wrap/Module.cpp | 151 +++++----------- wrap/Qualified.h | 97 ++++++++--- wrap/ReturnType.cpp | 8 +- wrap/ReturnType.h | 10 +- wrap/TemplateInstantiationTypedef.cpp | 6 +- wrap/TemplateSubstitution.h | 10 +- wrap/TypeAttributesTable.cpp | 2 +- wrap/tests/geometry.h | 240 +++++++++++++------------- wrap/tests/testArgument.cpp | 16 +- wrap/tests/testClass.cpp | 2 +- wrap/tests/testMethod.cpp | 96 +++++++++++ wrap/tests/testType.cpp | 29 +--- wrap/tests/testWrap.cpp | 82 ++++----- 20 files changed, 445 insertions(+), 388 deletions(-) diff --git a/wrap/Argument.cpp b/wrap/Argument.cpp index 6a5675a44..1f57917d8 100644 --- a/wrap/Argument.cpp +++ b/wrap/Argument.cpp @@ -50,25 +50,25 @@ ArgumentList ArgumentList::expandTemplate( /* ************************************************************************* */ string Argument::matlabClass(const string& delim) const { string result; - BOOST_FOREACH(const string& ns, type.namespaces) + BOOST_FOREACH(const string& ns, type.namespaces()) result += ns + delim; - if (type.name == "string" || type.name == "unsigned char" - || type.name == "char") + if (type.name() == "string" || type.name() == "unsigned char" + || type.name() == "char") return result + "char"; - if (type.name == "Vector" || type.name == "Matrix") + if (type.name() == "Vector" || type.name() == "Matrix") return result + "double"; - if (type.name == "int" || type.name == "size_t") + if (type.name() == "int" || type.name() == "size_t") return result + "numeric"; - if (type.name == "bool") + if (type.name() == "bool") return result + "logical"; - return result + type.name; + return result + type.name(); } /* ************************************************************************* */ bool Argument::isScalar() const { - return (type.name == "bool" || type.name == "char" - || type.name == "unsigned char" || type.name == "int" - || type.name == "size_t" || type.name == "double"); + return (type.name() == "bool" || type.name() == "char" + || type.name() == "unsigned char" || type.name() == "int" + || type.name() == "size_t" || type.name() == "double"); } /* ************************************************************************* */ @@ -102,7 +102,7 @@ void Argument::matlab_unwrap(FileWriter& file, const string& matlabName) const { /* ************************************************************************* */ void Argument::proxy_check(FileWriter& proxyFile, const string& s) const { proxyFile.oss << "isa(" << s << ",'" << matlabClass(".") << "')"; - if (type.name == "Vector") + if (type.name() == "Vector") proxyFile.oss << " && size(" << s << ",2)==1"; } @@ -113,7 +113,7 @@ string ArgumentList::types() const { BOOST_FOREACH(Argument arg, *this) { if (!first) str += ","; - str += arg.type.name; + str += arg.type.name(); first = false; } return str; @@ -125,14 +125,14 @@ string ArgumentList::signature() const { bool cap = false; BOOST_FOREACH(Argument arg, *this) { - BOOST_FOREACH(char ch, arg.type.name) + BOOST_FOREACH(char ch, arg.type.name()) if (isupper(ch)) { sig += ch; //If there is a capital letter, we don't want to read it below cap = true; } if (!cap) - sig += arg.type.name[0]; + sig += arg.type.name()[0]; //Reset to default cap = false; } @@ -179,7 +179,7 @@ void ArgumentList::emit_prototype(FileWriter& file, const string& name) const { BOOST_FOREACH(Argument arg, *this) { if (!first) file.oss << ", "; - file.oss << arg.type.name << " " << arg.name; + file.oss << arg.type.name() << " " << arg.name; first = false; } file.oss << ")"; diff --git a/wrap/Class.cpp b/wrap/Class.cpp index 93135498f..cfafd0ce5 100644 --- a/wrap/Class.cpp +++ b/wrap/Class.cpp @@ -57,7 +57,7 @@ void Class::matlab_proxy(Str toolboxPath, Str wrapperName, vector& functionNames) const { // Create namespace folders - createNamespaceStructure(namespaces, toolboxPath); + createNamespaceStructure(namespaces(), toolboxPath); // open destination classFile string classFile = matlabName(toolboxPath); @@ -74,14 +74,14 @@ void Class::matlab_proxy(Str toolboxPath, Str wrapperName, // we want our class to inherit the handle class for memory purposes const string parent = qualifiedParent.empty() ? "handle" : matlabBaseName; comment_fragment(proxyFile); - proxyFile.oss << "classdef " << name << " < " << parent << endl; + proxyFile.oss << "classdef " << name() << " < " << parent << endl; proxyFile.oss << " properties\n"; proxyFile.oss << " ptr_" << matlabUniqueName << " = 0\n"; proxyFile.oss << " end\n"; proxyFile.oss << " methods\n"; // Constructor - proxyFile.oss << " function obj = " << name << "(varargin)\n"; + proxyFile.oss << " function obj = " << name() << "(varargin)\n"; // Special pointer constructors - one in MATLAB to create an object and // assign a pointer returned from a C++ function. In turn this MATLAB // constructor calls a special C++ function that just adds the object to @@ -266,7 +266,7 @@ Class Class::expandTemplate(const TemplateSubstitution& ts) const { inst.methods_ = expandMethodTemplate(methods_, ts); inst.static_methods = expandMethodTemplate(static_methods, ts); inst.constructor = constructor.expandTemplate(ts); - inst.deconstructor.name = inst.name; + inst.deconstructor.name = inst.name(); return inst; } @@ -276,10 +276,10 @@ vector Class::expandTemplate(Str templateArg, vector result; BOOST_FOREACH(const Qualified& instName, instantiations) { Qualified expandedClass = (Qualified) (*this); - expandedClass.name += instName.name; + expandedClass.expand(instName.name()); const TemplateSubstitution ts(templateArg, instName, expandedClass); Class inst = expandTemplate(ts); - inst.name = expandedClass.name; + inst.name_ = expandedClass.name(); inst.templateArgs.clear(); inst.typedefName = qualifiedName("::") + "<" + instName.qualifiedName("::") + ">"; @@ -297,14 +297,14 @@ void Class::addMethod(bool verbose, bool is_const, Str methodName, // Create method to expand // For all values of the template argument, create a new method BOOST_FOREACH(const Qualified& instName, templateArgValues) { - const TemplateSubstitution ts(templateArgName, instName, this->name); + const TemplateSubstitution ts(templateArgName, instName, name()); // substitute template in arguments ArgumentList expandedArgs = argumentList.expandTemplate(ts); // do the same for return type ReturnValue expandedRetVal = returnValue.expandTemplate(ts); // Now stick in new overload stack with expandedMethodName key // but note we use the same, unexpanded methodName in overload - string expandedMethodName = methodName + instName.name; + string expandedMethodName = methodName + instName.name(); methods_[expandedMethodName].addOverload(methodName, expandedArgs, expandedRetVal, is_const, instName, verbose); } @@ -369,7 +369,7 @@ void Class::appendInheritedMethods(const Class& cls, // Find parent BOOST_FOREACH(const Class& parent, classes) { // We found a parent class for our parent, TODO improve ! - if (parent.name == cls.qualifiedParent.name) { + if (parent.name() == cls.qualifiedParent.name()) { methods_.insert(parent.methods_.begin(), parent.methods_.end()); appendInheritedMethods(parent, classes); } @@ -380,11 +380,11 @@ void Class::appendInheritedMethods(const Class& cls, /* ************************************************************************* */ string Class::getTypedef() const { string result; - BOOST_FOREACH(Str namesp, namespaces) { + BOOST_FOREACH(Str namesp, namespaces()) { result += ("namespace " + namesp + " { "); } - result += ("typedef " + typedefName + " " + name + ";"); - for (size_t i = 0; i < namespaces.size(); ++i) { + result += ("typedef " + typedefName + " " + name() + ";"); + for (size_t i = 0; i < namespaces().size(); ++i) { result += " }"; } return result; @@ -392,7 +392,7 @@ string Class::getTypedef() const { /* ************************************************************************* */ void Class::comment_fragment(FileWriter& proxyFile) const { - proxyFile.oss << "%class " << name << ", see Doxygen page for details\n"; + proxyFile.oss << "%class " << name() << ", see Doxygen page for details\n"; proxyFile.oss << "%at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html\n"; @@ -412,7 +412,7 @@ void Class::comment_fragment(FileWriter& proxyFile) const { proxyFile.oss << "%\n%-------Serialization Interface-------\n"; proxyFile.oss << "%string_serialize() : returns string\n"; proxyFile.oss << "%string_deserialize(string serialized) : returns " - << this->name << "\n"; + << name() << "\n"; } proxyFile.oss << "%\n"; @@ -605,12 +605,12 @@ string Class::getSerializationExport() const { /* ************************************************************************* */ void Class::python_wrapper(FileWriter& wrapperFile) const { - wrapperFile.oss << "class_<" << name << ">(\"" << name << "\")\n"; - constructor.python_wrapper(wrapperFile, name); + wrapperFile.oss << "class_<" << name() << ">(\"" << name() << "\")\n"; + constructor.python_wrapper(wrapperFile, name()); BOOST_FOREACH(const StaticMethod& m, static_methods | boost::adaptors::map_values) - m.python_wrapper(wrapperFile, name); + m.python_wrapper(wrapperFile, name()); BOOST_FOREACH(const Method& m, methods_ | boost::adaptors::map_values) - m.python_wrapper(wrapperFile, name); + m.python_wrapper(wrapperFile, name()); wrapperFile.oss << ";\n\n"; } diff --git a/wrap/Class.h b/wrap/Class.h index 9e4dff13d..244bcbac6 100644 --- a/wrap/Class.h +++ b/wrap/Class.h @@ -117,7 +117,7 @@ public: void python_wrapper(FileWriter& wrapperFile) const; friend std::ostream& operator<<(std::ostream& os, const Class& cls) { - os << "class " << cls.name << "{\n"; + os << "class " << cls.name() << "{\n"; os << cls.constructor << ";\n"; BOOST_FOREACH(const StaticMethod& m, cls.static_methods | boost::adaptors::map_values) os << m << ";\n"; diff --git a/wrap/Function.cpp b/wrap/Function.cpp index d045d2915..63b561dfd 100644 --- a/wrap/Function.cpp +++ b/wrap/Function.cpp @@ -42,7 +42,7 @@ bool Function::initializeOrCheck(const string& name, const Qualified& instName, verbose_ = verbose; return true; } else { - if (name_ != name || templateArgValue_ != instName || verbose_ != verbose) + if (name_ != name || !(templateArgValue_ == instName) || verbose_ != verbose) throw runtime_error( "Function::initializeOrCheck called with different arguments: with name " + name + " instead of expected " + name_ diff --git a/wrap/Function.h b/wrap/Function.h index 249cd42a7..2f52f07c1 100644 --- a/wrap/Function.h +++ b/wrap/Function.h @@ -53,7 +53,7 @@ public: if (templateArgValue_.empty()) return name_; else - return name_ + templateArgValue_.name; + return name_ + templateArgValue_.name(); } /// Emit function call to MATLAB (no argument checking) diff --git a/wrap/GlobalFunction.cpp b/wrap/GlobalFunction.cpp index dfeb46dce..f31bb4a93 100644 --- a/wrap/GlobalFunction.cpp +++ b/wrap/GlobalFunction.cpp @@ -19,8 +19,8 @@ using namespace std; void GlobalFunction::addOverload(const Qualified& overload, const ArgumentList& args, const ReturnValue& retVal, const Qualified& instName, bool verbose) { - string name(overload.name); - FullyOverloadedFunction::addOverload(name, args, retVal, instName, verbose); + FullyOverloadedFunction::addOverload(overload.name(), args, retVal, instName, + verbose); overloads.push_back(overload); } @@ -37,7 +37,7 @@ void GlobalFunction::matlab_proxy(const string& toolboxPath, for (size_t i = 0; i < overloads.size(); ++i) { Qualified overload = overloads.at(i); // use concatenated namespaces as key - string str_ns = qualifiedName("", overload.namespaces); + string str_ns = qualifiedName("", overload.namespaces()); const ReturnValue& ret = returnValue(i); const ArgumentList& args = argumentList(i); grouped_functions[str_ns].addOverload(overload, args, ret); @@ -59,7 +59,7 @@ void GlobalFunction::generateSingleFunction(const string& toolboxPath, // create the folder for the namespace const Qualified& overload1 = overloads.front(); - createNamespaceStructure(overload1.namespaces, toolboxPath); + createNamespaceStructure(overload1.namespaces(), toolboxPath); // open destination mfunctionFileName string mfunctionFileName = overload1.matlabName(toolboxPath); @@ -104,7 +104,7 @@ void GlobalFunction::generateSingleFunction(const string& toolboxPath, args.matlab_unwrap(file, 0); // We start at 0 because there is no self object // call method with default type and wrap result - if (returnVal.type1.name != "void") + if (returnVal.type1.name() != "void") returnVal.wrap_result(cppName + "(" + args.names() + ")", file, typeAttributes); else diff --git a/wrap/MethodBase.cpp b/wrap/MethodBase.cpp index 643d8ceec..48513e4ac 100644 --- a/wrap/MethodBase.cpp +++ b/wrap/MethodBase.cpp @@ -123,7 +123,7 @@ string MethodBase::wrapper_fragment(FileWriter& wrapperFile, Str cppClassName, args, instName); expanded += ("(" + args.names() + ")"); - if (returnVal.type1.name != "void") + if (returnVal.type1.name() != "void") returnVal.wrap_result(expanded, wrapperFile, typeAttributes); else wrapperFile.oss << " " + expanded + ";\n"; diff --git a/wrap/Module.cpp b/wrap/Module.cpp index 912397f21..90fabda8a 100644 --- a/wrap/Module.cpp +++ b/wrap/Module.cpp @@ -25,9 +25,6 @@ //#define BOOST_SPIRIT_DEBUG #include "spirit_actors.h" -#include -#include -#include #ifdef __GNUC__ #pragma GCC diagnostic push #pragma GCC diagnostic ignored "-Wunused-variable" @@ -51,8 +48,6 @@ using namespace BOOST_SPIRIT_CLASSIC_NS; namespace bl = boost::lambda; namespace fs = boost::filesystem; -typedef rule Rule; - /* ************************************************************************* */ // We parse an interface file into a Module object. // The grammar is defined using the boost/spirit combinatorial parser. @@ -102,7 +97,6 @@ Module::Module(const string& interfacePath, void Module::parseMarkup(const std::string& data) { // The parse imperatively :-( updates variables gradually during parse // The one with postfix 0 are used to reset the variables after parse. - vector namespaces; // current namespace tag //---------------------------------------------------------------------------- // Grammar with actions that build the Class object. Actions are @@ -113,129 +107,74 @@ void Module::parseMarkup(const std::string& data) { // http://www.boost.org/doc/libs/1_37_0/libs/spirit/classic/doc/directives.html // ---------------------------------------------------------------------------- - Rule comments_p = comment_p("/*", "*/") | comment_p("//", eol_p); - - Rule basisType_p = - (str_p("string") | "bool" | "size_t" | "int" | "double" | "char" | "unsigned char"); - - Rule keywords_p = - (str_p("const") | "static" | "namespace" | "void" | basisType_p); - - Rule eigenType_p = - (str_p("Vector") | "Matrix"); - - //Rule for STL Containers (class names are lowercase) - Rule stlType_p = (str_p("vector") | "list"); - - Rule className_p = (lexeme_d[upper_p >> *(alnum_p | '_')] - eigenType_p - keywords_p) | stlType_p; - - Rule namespace_name_p = lexeme_d[lower_p >> *(alnum_p | '_')] - keywords_p; - - Argument arg0, arg; - Rule namespace_arg_p = namespace_name_p - [push_back_a(arg.type.namespaces)] >> str_p("::"); - - Rule argEigenType_p = - eigenType_p[assign_a(arg.type.name)]; - - Rule eigenRef_p = - !str_p("const") [assign_a(arg.is_const,true)] >> - eigenType_p [assign_a(arg.type.name)] >> - ch_p('&') [assign_a(arg.is_ref,true)]; - - Rule classArg_p = - !str_p("const") [assign_a(arg.is_const,true)] >> - *namespace_arg_p >> - className_p[assign_a(arg.type.name)] >> - !ch_p('&')[assign_a(arg.is_ref,true)]; - - Rule name_p = lexeme_d[alpha_p >> *(alnum_p | '_')]; + // Define Rule and instantiate basic rules + typedef rule Rule; + basic_rules basic; // TODO, do we really need cls here? Non-local Class cls0(verbose),cls(verbose); - Rule classParent_p = - *(namespace_name_p[push_back_a(cls.qualifiedParent.namespaces)] >> str_p("::")) >> - className_p[assign_a(cls.qualifiedParent.name)]; + TypeGrammar classParent_p(cls.qualifiedParent); // parse "gtsam::Pose2" and add to templateArgValues Qualified templateArgValue; vector templateArgValues; Rule templateArgValue_p = - (*(namespace_name_p[push_back_a(templateArgValue.namespaces)] >> str_p("::")) >> - (className_p | eigenType_p)[assign_a(templateArgValue.name)]) - [push_back_a(templateArgValues, templateArgValue)] - [clear_a(templateArgValue)]; + TypeGrammar(templateArgValue) + [push_back_a( templateArgValues, templateArgValue)]; // template string templateArgName; Rule templateArgValues_p = (str_p("template") >> - '<' >> name_p[assign_a(templateArgName)] >> '=' >> + '<' >> basic.name_p[assign_a(templateArgName)] >> '=' >> '{' >> !(templateArgValue_p >> *(',' >> templateArgValue_p)) >> '}' >> '>'); // parse "gtsam::Pose2" and add to singleInstantiation.typeList - TemplateInstantiationTypedef singleInstantiation; + TemplateInstantiationTypedef singleInstantiation, singleInstantiation0; Rule templateSingleInstantiationArg_p = - (*(namespace_name_p[push_back_a(templateArgValue.namespaces)] >> str_p("::")) >> - (className_p | eigenType_p)[assign_a(templateArgValue.name)]) - [push_back_a(singleInstantiation.typeList, templateArgValue)] - [clear_a(templateArgValue)]; + TypeGrammar(templateArgValue) + [push_back_a(singleInstantiation.typeList, templateArgValue)]; // typedef gtsam::RangeFactor RangeFactorPosePoint2; - TemplateInstantiationTypedef singleInstantiation0; Rule templateSingleInstantiation_p = (str_p("typedef") >> - *(namespace_name_p[push_back_a(singleInstantiation.class_.namespaces)] >> str_p("::")) >> - className_p[assign_a(singleInstantiation.class_.name)] >> - '<' >> templateSingleInstantiationArg_p >> *(',' >> templateSingleInstantiationArg_p) >> - '>' >> - className_p[assign_a(singleInstantiation.name)] >> + TypeGrammar(singleInstantiation.class_) >> + '<' >> templateSingleInstantiationArg_p >> *(',' >> templateSingleInstantiationArg_p) >> '>' >> + TypeGrammar(singleInstantiation) >> ';') - [assign_a(singleInstantiation.namespaces, namespaces)] [push_back_a(templateInstantiationTypedefs, singleInstantiation)] [assign_a(singleInstantiation, singleInstantiation0)]; // template Rule templateList_p = (str_p("template") >> - '<' >> name_p[push_back_a(cls.templateArgs)] >> *(',' >> name_p[push_back_a(cls.templateArgs)]) >> + '<' >> basic.name_p[push_back_a(cls.templateArgs)] >> *(',' >> basic.name_p[push_back_a(cls.templateArgs)]) >> '>'); // NOTE: allows for pointers to all types + // Slightly more permissive than before on basis/eigen type qualification ArgumentList args; - Rule argument_p = - ((basisType_p[assign_a(arg.type.name)] | argEigenType_p | eigenRef_p | classArg_p) - >> !ch_p('*')[assign_a(arg.is_ptr,true)] - >> name_p[assign_a(arg.name)]) - [push_back_a(args, arg)] - [assign_a(arg,arg0)]; + Argument arg0, arg; + TypeGrammar argument_type_g(arg.type); + Rule argument_p = + !str_p("const")[assign_a(arg.is_const, true)] + >> argument_type_g + >> (!ch_p('&')[assign_a(arg.is_ref, true)] | !ch_p('*')[assign_a(arg.is_ptr, true)]) + [push_back_a(args, arg)] + [assign_a(arg,arg0)]; Rule argumentList_p = !argument_p >> * (',' >> argument_p); // parse class constructor Constructor constructor0(verbose), constructor(verbose); Rule constructor_p = - (className_p >> '(' >> argumentList_p >> ')' >> ';' >> !comments_p) + (basic.className_p >> '(' >> argumentList_p >> ')' >> ';' >> !basic.comments_p) [bl::bind(&Constructor::push_back, bl::var(constructor), bl::var(args))] [clear_a(args)]; - vector namespaces_return; /// namespace for current return type - Rule namespace_ret_p = namespace_name_p[push_back_a(namespaces_return)] >> str_p("::"); - - // HACK: use const values instead of using enums themselves - somehow this doesn't result in values getting assigned to gibberish - static const ReturnType::return_category RETURN_EIGEN = ReturnType::EIGEN; - static const ReturnType::return_category RETURN_BASIS = ReturnType::BASIS; - static const ReturnType::return_category RETURN_CLASS = ReturnType::CLASS; - static const ReturnType::return_category RETURN_VOID = ReturnType::VOID; - ReturnType retType0, retType; - Rule returnType_p = - (basisType_p[assign_a(retType.name)][assign_a(retType.category, RETURN_BASIS)]) | - ((*namespace_ret_p)[assign_a(retType.namespaces, namespaces_return)][clear_a(namespaces_return)] - >> (className_p[assign_a(retType.name)][assign_a(retType.category, RETURN_CLASS)]) >> - !ch_p('*')[assign_a(retType.isPtr,true)]) | - (eigenType_p[assign_a(retType.name)][assign_a(retType.category, RETURN_EIGEN)]); + Rule returnType_p = TypeGrammar(retType); ReturnValue retVal0, retVal; Rule returnType1_p = returnType_p[assign_a(retVal.type1,retType)][assign_a(retType,retType0)]; @@ -245,9 +184,7 @@ void Module::parseMarkup(const std::string& data) { (str_p("pair") >> '<' >> returnType1_p >> ',' >> returnType2_p >> '>') [assign_a(retVal.isPair,true)]; - Rule void_p = str_p("void")[assign_a(retVal.type1.name)][assign_a(retVal.type1.category, RETURN_VOID)]; - - Rule returnValue_p = void_p | pair_p | returnType1_p; + Rule returnValue_p = pair_p | returnType1_p; Rule methodName_p = lexeme_d[(upper_p | lower_p) >> *(alnum_p | '_')]; @@ -258,7 +195,7 @@ void Module::parseMarkup(const std::string& data) { !templateArgValues_p >> (returnValue_p >> methodName_p[assign_a(methodName)] >> '(' >> argumentList_p >> ')' >> - !str_p("const")[assign_a(isConst,true)] >> ';' >> *comments_p) + !str_p("const")[assign_a(isConst,true)] >> ';' >> *basic.comments_p) [bl::bind(&Class::addMethod, bl::var(cls), verbose, bl::var(isConst), bl::var(methodName), bl::var(args), bl::var(retVal), bl::var(templateArgName), bl::var(templateArgValues))] @@ -271,7 +208,7 @@ void Module::parseMarkup(const std::string& data) { Rule static_method_p = (str_p("static") >> returnValue_p >> staticMethodName_p[assign_a(methodName)] >> - '(' >> argumentList_p >> ')' >> ';' >> *comments_p) + '(' >> argumentList_p >> ')' >> ';' >> *basic.comments_p) [bl::bind(&StaticMethod::addOverload, bl::var(cls.static_methods)[bl::var(methodName)], bl::var(methodName), bl::var(args), bl::var(retVal), Qualified(),verbose)] @@ -281,6 +218,7 @@ void Module::parseMarkup(const std::string& data) { Rule functions_p = constructor_p | method_p | static_method_p; // parse a full class + vector namespaces; // current namespace tag vector templateInstantiations; Rule class_p = eps_p[assign_a(cls,cls0)] @@ -291,15 +229,15 @@ void Module::parseMarkup(const std::string& data) { | templateList_p) >> !(str_p("virtual")[assign_a(cls.isVirtual, true)]) >> str_p("class") - >> className_p[assign_a(cls.name)] + >> basic.className_p[assign_a(cls.name_)] >> ((':' >> classParent_p >> '{') | '{') - >> *(functions_p | comments_p) + >> *(functions_p | basic.comments_p) >> str_p("};")) [bl::bind(&Constructor::initializeOrCheck, bl::var(constructor), - bl::var(cls.name), Qualified(), verbose)] + bl::var(cls.name_), Qualified(), verbose)] [assign_a(cls.constructor, constructor)] - [assign_a(cls.namespaces, namespaces)] - [assign_a(cls.deconstructor.name,cls.name)] + [assign_a(cls.namespaces_, namespaces)] + [assign_a(cls.deconstructor.name,cls.name_)] [bl::bind(&handle_possible_template, bl::var(classes), bl::var(cls), bl::var(templateInstantiations))] [clear_a(templateInstantiations)] @@ -309,11 +247,11 @@ void Module::parseMarkup(const std::string& data) { // parse a global function Qualified globalFunction; Rule global_function_p = - (returnValue_p >> staticMethodName_p[assign_a(globalFunction.name)] >> - '(' >> argumentList_p >> ')' >> ';' >> *comments_p) - [assign_a(globalFunction.namespaces,namespaces)] + (returnValue_p >> staticMethodName_p[assign_a(globalFunction.name_)] >> + '(' >> argumentList_p >> ')' >> ';' >> *basic.comments_p) + [assign_a(globalFunction.namespaces_,namespaces)] [bl::bind(&GlobalFunction::addOverload, - bl::var(global_functions)[bl::var(globalFunction.name)], + bl::var(global_functions)[bl::var(globalFunction.name_)], bl::var(globalFunction), bl::var(args), bl::var(retVal), Qualified(),verbose)] [assign_a(retVal,retVal0)] [clear_a(globalFunction)] @@ -328,9 +266,9 @@ void Module::parseMarkup(const std::string& data) { Rule namespace_def_p = (str_p("namespace") - >> namespace_name_p[push_back_a(namespaces)] + >> basic.namepsace_p[push_back_a(namespaces)] >> ch_p('{') - >> *(include_p | class_p | templateSingleInstantiation_p | global_function_p | namespace_def_p | comments_p) + >> *(include_p | class_p | templateSingleInstantiation_p | global_function_p | namespace_def_p | basic.comments_p) >> ch_p('}')) [pop_a(namespaces)]; @@ -343,17 +281,20 @@ void Module::parseMarkup(const std::string& data) { Rule forward_declaration_p = !(str_p("virtual")[assign_a(fwDec.isVirtual, true)]) >> str_p("class") - >> (*(namespace_name_p >> str_p("::")) >> className_p)[assign_a(fwDec.name)] + >> (*(basic.namepsace_p >> str_p("::")) >> basic.className_p)[assign_a(fwDec.name)] >> ch_p(';') [push_back_a(forward_declarations, fwDec)] [assign_a(fwDec, fwDec0)]; - Rule module_content_p = comments_p | include_p | class_p | templateSingleInstantiation_p | forward_declaration_p | global_function_p | namespace_def_p; + Rule module_content_p = basic.comments_p | include_p | class_p + | templateSingleInstantiation_p | forward_declaration_p + | global_function_p | namespace_def_p; Rule module_p = *module_content_p >> !end_p; //---------------------------------------------------------------------------- // for debugging, define BOOST_SPIRIT_DEBUG +#define BOOST_SPIRIT_DEBUG # ifdef BOOST_SPIRIT_DEBUG BOOST_SPIRIT_DEBUG_NODE(className_p); BOOST_SPIRIT_DEBUG_NODE(classPtr_p); @@ -381,7 +322,7 @@ void Module::parseMarkup(const std::string& data) { if(!info.full) { printf("parsing stopped at \n%.20s\n",info.stop); cout << "Stopped near:\n" - "class '" << cls.name << "'\n" + "class '" << cls.name() << "'\n" "method '" << methodName << "'\n" "argument '" << arg.name << "'" << endl; throw ParseFailed((int)info.length); diff --git a/wrap/Qualified.h b/wrap/Qualified.h index 1468c8d17..72d1b1c4f 100644 --- a/wrap/Qualified.h +++ b/wrap/Qualified.h @@ -34,10 +34,18 @@ namespace wrap { /** * Class to encapuslate a qualified name, i.e., with (nested) namespaces */ -struct Qualified { +class Qualified { - std::vector namespaces; ///< Stack of namespaces - std::string name; ///< type name +//protected: +public: + + std::vector namespaces_; ///< Stack of namespaces + std::string name_; ///< type name + + friend class TypeGrammar; + friend class TemplateSubstitution; + +public: /// the different categories typedef enum { @@ -49,43 +57,76 @@ struct Qualified { category(VOID) { } - Qualified(const std::string& name_, Category c = CLASS) : - name(name_), category(c) { + Qualified(const std::string& n, Category c = CLASS) : + name_(n), category(c) { + } + + Qualified(const std::string& ns1, const std::string& ns2, + const std::string& n, Category c = CLASS) : + name_(n), category(c) { + namespaces_.push_back(ns1); + namespaces_.push_back(ns2); + } + + Qualified(const std::string& ns1, const std::string& n, Category c = CLASS) : + name_(n), category(c) { + namespaces_.push_back(ns1); + } + + std::string name() const { + return name_; + } + + std::vector namespaces() const { + return namespaces_; + } + + // Qualified is 'abused' as template argument name as well + // this function checks whether *this matches with templateArg + bool match(const std::string& templateArg) const { + return (name_ == templateArg && namespaces_.empty() && category == CLASS); + } + + void rename(const Qualified& q) { + namespaces_ = q.namespaces_; + name_ = q.name_; + category = q.category; + } + + void expand(const std::string& expansion) { + name_ += expansion; } bool operator==(const Qualified& other) const { - return namespaces == other.namespaces && name == other.name + return namespaces_ == other.namespaces_ && name_ == other.name_ && category == other.category; } bool empty() const { - return namespaces.empty() && name.empty(); + return namespaces_.empty() && name_.empty(); } void clear() { - namespaces.clear(); - name.clear(); - } - - bool operator!=(const Qualified& other) const { - return other.name != name || other.namespaces != namespaces; + namespaces_.clear(); + name_.clear(); + category = VOID; } /// Return a qualified string using given delimiter std::string qualifiedName(const std::string& delimiter = "") const { std::string result; - for (std::size_t i = 0; i < namespaces.size(); ++i) - result += (namespaces[i] + delimiter); - result += name; + for (std::size_t i = 0; i < namespaces_.size(); ++i) + result += (namespaces_[i] + delimiter); + result += name_; return result; } /// Return a matlab file name, i.e. "toolboxPath/+ns1/+ns2/name.m" std::string matlabName(const std::string& toolboxPath) const { std::string result = toolboxPath; - for (std::size_t i = 0; i < namespaces.size(); ++i) - result += ("/+" + namespaces[i]); - result += "/" + name + ".m"; + for (std::size_t i = 0; i < namespaces_.size(); ++i) + result += ("/+" + namespaces_[i]); + result += "/" + name_ + ".m"; return result; } @@ -130,12 +171,14 @@ struct basic_rules { }; // http://boost-spirit.com/distrib/spirit_1_8_2/libs/spirit/doc/grammar.html -struct type_grammar: public classic::grammar { +class TypeGrammar: public classic::grammar { wrap::Qualified& result_; ///< successful parse will be placed in here +public: + /// Construct type grammar and specify where result is placed - type_grammar(wrap::Qualified& result) : + TypeGrammar(wrap::Qualified& result) : result_(result) { } @@ -148,7 +191,7 @@ struct type_grammar: public classic::grammar { Rule void_p, my_basisType_p, my_eigenType_p, namespace_del_p, class_p, type_p; - definition(type_grammar const& self) { + definition(TypeGrammar const& self) { using namespace wrap; using namespace classic; @@ -159,22 +202,22 @@ struct type_grammar: public classic::grammar { static const Qualified::Category CLASS = Qualified::CLASS; static const Qualified::Category VOID = Qualified::VOID; - void_p = str_p("void")[assign_a(self.result_.name)] // + void_p = str_p("void")[assign_a(self.result_.name_)] // [assign_a(self.result_.category, VOID)]; my_basisType_p = basic_rules::basisType_p // - [assign_a(self.result_.name)] // + [assign_a(self.result_.name_)] // [assign_a(self.result_.category, BASIS)]; my_eigenType_p = basic_rules::eigenType_p // - [assign_a(self.result_.name)] // + [assign_a(self.result_.name_)] // [assign_a(self.result_.category, EIGEN)]; namespace_del_p = basic_rules::namepsace_p // - [push_back_a(self.result_.namespaces)] >> str_p("::"); + [push_back_a(self.result_.namespaces_)] >> str_p("::"); class_p = *namespace_del_p >> basic_rules::className_p // - [assign_a(self.result_.name)] // + [assign_a(self.result_.name_)] // [assign_a(self.result_.category, CLASS)]; type_p = void_p | my_basisType_p | my_eigenType_p | class_p; diff --git a/wrap/ReturnType.cpp b/wrap/ReturnType.cpp index 25147e59a..f41a45e56 100644 --- a/wrap/ReturnType.cpp +++ b/wrap/ReturnType.cpp @@ -14,7 +14,7 @@ using namespace wrap; /* ************************************************************************* */ string ReturnType::str(bool add_ptr) const { - return maybe_shared_ptr(add_ptr && isPtr, qualifiedName("::"), name); + return maybe_shared_ptr(add_ptr && isPtr, qualifiedName("::"), name()); } /* ************************************************************************* */ @@ -25,7 +25,7 @@ void ReturnType::wrap_result(const string& out, const string& result, if (category == CLASS) { string objCopy, ptrType; - ptrType = "Shared" + name; + ptrType = "Shared" + name(); const bool isVirtual = typeAttributes.attributes(cppType).isVirtual; if (isVirtual) { if (isPtr) @@ -41,7 +41,7 @@ void ReturnType::wrap_result(const string& out, const string& result, wrapperFile.oss << out << " = wrap_shared_ptr(" << objCopy << ",\"" << matlabType << "\", " << (isVirtual ? "true" : "false") << ");\n"; } else if (isPtr) { - wrapperFile.oss << " Shared" << name << "* ret = new Shared" << name << "(" + wrapperFile.oss << " Shared" << name() << "* ret = new Shared" << name() << "(" << result << ");" << endl; wrapperFile.oss << out << " = wrap_shared_ptr(ret,\"" << matlabType << "\");\n"; @@ -54,7 +54,7 @@ void ReturnType::wrap_result(const string& out, const string& result, void ReturnType::wrapTypeUnwrap(FileWriter& wrapperFile) const { if (category == CLASS) wrapperFile.oss << " typedef boost::shared_ptr<" << qualifiedName("::") - << "> Shared" << name << ";" << endl; + << "> Shared" << name() << ";" << endl; } /* ************************************************************************* */ diff --git a/wrap/ReturnType.h b/wrap/ReturnType.h index a56e31a24..e619a18d1 100644 --- a/wrap/ReturnType.h +++ b/wrap/ReturnType.h @@ -21,18 +21,14 @@ struct ReturnType: Qualified { bool isPtr; + /// Makes a void type ReturnType() : isPtr(false) { } + /// Make a Class type, no namespaces ReturnType(const std::string& name) : - isPtr(false) { - Qualified::name = name; - } - - void rename(const Qualified& q) { - name = q.name; - namespaces = q.namespaces; + Qualified(name,Qualified::CLASS), isPtr(false) { } /// Check if this type is in a set of valid types diff --git a/wrap/TemplateInstantiationTypedef.cpp b/wrap/TemplateInstantiationTypedef.cpp index 2007acdf1..e925fd381 100644 --- a/wrap/TemplateInstantiationTypedef.cpp +++ b/wrap/TemplateInstantiationTypedef.cpp @@ -32,7 +32,7 @@ Class TemplateInstantiationTypedef::findAndExpand( // Find matching class boost::optional matchedClass; BOOST_FOREACH(const Class& cls, classes) { - if (cls.name == class_.name && cls.namespaces == class_.namespaces + if (cls.name() == class_.name() && cls.namespaces() == class_.namespaces() && cls.templateArgs.size() == typeList.size()) { matchedClass.reset(cls); break; @@ -52,7 +52,8 @@ Class TemplateInstantiationTypedef::findAndExpand( } // Fix class properties - classInst.name = name; + classInst.name_ = name(); + classInst.namespaces_ = namespaces(); classInst.templateArgs.clear(); classInst.typedefName = matchedClass->qualifiedName("::") + "<"; if (typeList.size() > 0) @@ -60,7 +61,6 @@ Class TemplateInstantiationTypedef::findAndExpand( for (size_t i = 1; i < typeList.size(); ++i) classInst.typedefName += (", " + typeList[i].qualifiedName("::")); classInst.typedefName += ">"; - classInst.namespaces = namespaces; return classInst; } diff --git a/wrap/TemplateSubstitution.h b/wrap/TemplateSubstitution.h index 52c29f571..7fe00e213 100644 --- a/wrap/TemplateSubstitution.h +++ b/wrap/TemplateSubstitution.h @@ -40,14 +40,14 @@ public: } std::string expandedClassName() const { - return expandedClass_.name; + return expandedClass_.name(); } // Substitute if needed Qualified tryToSubstitite(const Qualified& type) const { - if (type.name == templateArg_ && type.namespaces.empty()) + if (type.match(templateArg_)) return qualifiedType_; - else if (type.name == "This") + else if (type.match("This")) return expandedClass_; else return type; @@ -56,9 +56,9 @@ public: // Substitute if needed ReturnType tryToSubstitite(const ReturnType& type) const { ReturnType instType = type; - if (type.name == templateArg_ && type.namespaces.empty()) + if (type.match(templateArg_)) instType.rename(qualifiedType_); - else if (type.name == "This") + else if (type.match("This")) instType.rename(expandedClass_); return instType; } diff --git a/wrap/TypeAttributesTable.cpp b/wrap/TypeAttributesTable.cpp index a836f2005..061e09005 100644 --- a/wrap/TypeAttributesTable.cpp +++ b/wrap/TypeAttributesTable.cpp @@ -68,7 +68,7 @@ void TypeAttributesTable::checkValidity(const vector& classes) const { if (!cls.qualifiedParent.empty() && !cls.isVirtual) throw AttributeError(cls.qualifiedName("::"), "Has a base class so needs to be declared virtual, change to 'virtual class " - + cls.name + " ...'"); + + cls.name() + " ...'"); // Check that parent is virtual as well Qualified parent = cls.qualifiedParent; if (!parent.empty() && !table_.at(parent.qualifiedName("::")).isVirtual) diff --git a/wrap/tests/geometry.h b/wrap/tests/geometry.h index 3fec21ab9..0675490f9 100644 --- a/wrap/tests/geometry.h +++ b/wrap/tests/geometry.h @@ -7,126 +7,128 @@ namespace gtsam { class Point2 { Point2(); - Point2(double x, double y); +// 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(); - - void serializable() const; // Sets flag and creates export, but does not make serialization functions +// 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(); +// +// void serializable() const; // Sets flag and creates export, but does not make serialization functions }; -class Point3 { - Point3(double x, double y, double z); - double norm() const; +} // end namespace should be removed - // 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 -}; - -} -// 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(); - - pair return_pair (Vector v, Matrix A) const; // intentionally the first method - - 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(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! -}; - - -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 - void 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; -}; - -// 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; - -// comments at the end! - -// even more comments at the end! +//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 +//}; +// +//} +//// 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(); +// +// pair return_pair (Vector v, Matrix A) const; // intentionally the first method +// +// 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(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! +//}; +// +// +//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 +// void 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; +//}; +// +//// 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; +// +//// comments at the end! +// +//// even more comments at the end! diff --git a/wrap/tests/testArgument.cpp b/wrap/tests/testArgument.cpp index 418923f23..8a50d694f 100644 --- a/wrap/tests/testArgument.cpp +++ b/wrap/tests/testArgument.cpp @@ -30,7 +30,7 @@ static const bool T = true; struct ArgumentGrammar: public classic::grammar { wrap::Argument& result_; ///< successful parse will be placed in here - type_grammar argument_type_g; + TypeGrammar argument_type_g; /// Construct type grammar and specify where result is placed ArgumentGrammar(wrap::Argument& result) : @@ -78,9 +78,7 @@ TEST( Argument, grammar ) { ArgumentGrammar g(actual); EXPECT(parse("const gtsam::Point2& p4", g, space_p).full); - EXPECT_LONGS_EQUAL(1, actual.type.namespaces.size()); - EXPECT(actual.type.namespaces[0]=="gtsam"); - EXPECT(actual.type.name=="Point2"); + EXPECT(actual.type==Qualified("gtsam","Point2",Qualified::CLASS)); EXPECT(actual.name=="p4"); EXPECT(actual.is_const); EXPECT(actual.is_ref); @@ -88,8 +86,7 @@ TEST( Argument, grammar ) { actual = arg0; EXPECT(parse("Point2& p", g, space_p).full); - EXPECT(actual.type.namespaces.empty()); - EXPECT(actual.type.name=="Point2"); + EXPECT(actual.type==Qualified("Point2",Qualified::CLASS)); EXPECT(actual.name=="p"); EXPECT(!actual.is_const); EXPECT(actual.is_ref); @@ -97,9 +94,7 @@ TEST( Argument, grammar ) { actual = arg0; EXPECT(parse("gtsam::Point2* p3", g, space_p).full); - EXPECT_LONGS_EQUAL(1, actual.type.namespaces.size()); - EXPECT(actual.type.namespaces[0]=="gtsam"); - EXPECT(actual.type.name=="Point2"); + EXPECT(actual.type==Qualified("gtsam","Point2",Qualified::CLASS)); EXPECT(actual.name=="p3"); EXPECT(!actual.is_const); EXPECT(!actual.is_ref); @@ -119,8 +114,7 @@ TEST( Argument, grammar ) { actual = arg0; EXPECT(parse("const Matrix& m", g, space_p).full); - EXPECT(actual.type.namespaces.empty()); - EXPECT(actual.type.name=="Matrix"); + EXPECT(actual.type==Qualified("Matrix",Qualified::EIGEN)); EXPECT(actual.name=="m"); EXPECT(actual.is_const); EXPECT(actual.is_ref); diff --git a/wrap/tests/testClass.cpp b/wrap/tests/testClass.cpp index d68daf4ba..6a59cd83a 100644 --- a/wrap/tests/testClass.cpp +++ b/wrap/tests/testClass.cpp @@ -64,7 +64,7 @@ TEST( Class, TemplatedMethods ) { bool verbose = true, is_const = true; ArgumentList args; Argument arg; - arg.type.name = "T"; + arg.type.name_ = "T"; args.push_back(arg); const ReturnValue retVal(ReturnType("T")); const string templateArgName("T"); diff --git a/wrap/tests/testMethod.cpp b/wrap/tests/testMethod.cpp index 5861bab4a..b94bd8f9f 100644 --- a/wrap/tests/testMethod.cpp +++ b/wrap/tests/testMethod.cpp @@ -42,6 +42,102 @@ TEST( Method, addOverload ) { EXPECT_LONGS_EQUAL(2, method.nrOverloads()); } +// http://boost-spirit.com/distrib/spirit_1_8_2/libs/spirit/doc/grammar.html +struct method_grammar: public classic::grammar { + + wrap::Method& result_; ///< successful parse will be placed in here + + ArgumentList args; + Argument arg0, arg; + TypeGrammar argument_type_g; + + ReturnType retType0, retType; + TypeGrammar returntype_g; + + ReturnValue retVal0, retVal; + + /// Construct type grammar and specify where result is placed + method_grammar(wrap::Method& result) : + result_(result), argument_type_g(arg.type), returntype_g(retType) { + } + + /// Definition of type grammar + template + struct definition: basic_rules { + + typedef classic::rule Rule; + + Rule templateArgValue_p, templateArgValues_p, argument_p, argumentList_p, + returnType1_p, returnType2_p, pair_p, returnValue_p, methodName_p, + method_p; + + definition(method_grammar const& self) { + + using namespace wrap; + using namespace classic; + +// Rule templateArgValue_p = type_grammar(self.templateArgValue); +// +// // template +// Rule templateArgValues_p = (str_p("template") >> '<' >> name_p >> '=' +// >> '{' >> !(templateArgValue_p >> *(',' >> templateArgValue_p)) >> '}' +// >> '>'); +// + // NOTE: allows for pointers to all types + // Slightly more permissive than before on basis/eigen type qualification + argument_p = // + !str_p("const")[assign_a(self.arg.is_const, true)] // + >> self.argument_type_g // + >> (!ch_p('&')[assign_a(self.arg.is_ref, true)] + | !ch_p('*')[assign_a(self.arg.is_ptr, true)]) // + [push_back_a(self.args, self.arg)] // + [assign_a(self.arg, self.arg0)]; + + argumentList_p = !argument_p >> *(',' >> argument_p); +// + returnType1_p = self.returntype_g // + [assign_a(self.retVal.type1, retType)] // + [assign_a(self.retType, self.retType0)]; + + returnType2_p = self.returntype_g // + [assign_a(self.retVal.type2, retType)] // + [assign_a(self.retType, self.retType0)]; + + pair_p = (str_p("pair") >> '<' >> returnType1_p >> ',' >> returnType2_p + >> '>')[assign_a(self.retVal.isPair, true)]; + + returnValue_p = pair_p | returnType1_p; + + methodName_p = lexeme_d[(upper_p | lower_p) >> *(alnum_p | '_')]; + + // gtsam::Values retract(const gtsam::VectorValues& delta) const; + method_p = +// !templateArgValues_p >> + (returnValue_p >> methodName_p >> '(' >> argumentList_p >> ')' + >> !str_p("const") >> ';' >> *basic_rules::comments_p); + } + + Rule const& start() const { + return method_p; + } + + }; +}; +// method_grammar + +//****************************************************************************** +TEST( Method, grammar ) { + + using classic::space_p; + + // Create type grammar that will place result in actual + Method actual; + method_grammar method_g(actual); + + // a class type with namespaces + EXPECT(parse("double x() const;", method_g, space_p).full); +} + /* ************************************************************************* */ int main() { TestResult tr; diff --git a/wrap/tests/testType.cpp b/wrap/tests/testType.cpp index 538bcef3e..45ffdb6de 100644 --- a/wrap/tests/testType.cpp +++ b/wrap/tests/testType.cpp @@ -29,51 +29,36 @@ TEST( Type, grammar ) { // Create type grammar that will place result in actual Qualified actual; - type_grammar type_g(actual); + TypeGrammar type_g(actual); // a class type with 2 namespaces EXPECT(parse("gtsam::internal::Point2", type_g, space_p).full); - EXPECT(actual.name=="Point2"); - EXPECT_LONGS_EQUAL(2, actual.namespaces.size()); - EXPECT(actual.namespaces[0]=="gtsam"); - EXPECT(actual.namespaces[1]=="internal"); - EXPECT(actual.category==Qualified::CLASS); + EXPECT(actual==Qualified("gtsam","internal","Point2",Qualified::CLASS)); actual.clear(); // a class type with 1 namespace EXPECT(parse("gtsam::Point2", type_g, space_p).full); - EXPECT(actual.name=="Point2"); - EXPECT_LONGS_EQUAL(1, actual.namespaces.size()); - EXPECT(actual.namespaces[0]=="gtsam"); - EXPECT(actual.category==Qualified::CLASS); + EXPECT(actual==Qualified("gtsam","Point2",Qualified::CLASS)); actual.clear(); // a class type with no namespaces EXPECT(parse("Point2", type_g, space_p).full); - EXPECT(actual.name=="Point2"); - EXPECT(actual.namespaces.empty()); - EXPECT(actual.category==Qualified::CLASS); + EXPECT(actual==Qualified("Point2",Qualified::CLASS)); actual.clear(); // an Eigen type EXPECT(parse("Vector", type_g, space_p).full); - EXPECT(actual.name=="Vector"); - EXPECT(actual.namespaces.empty()); - EXPECT(actual.category==Qualified::EIGEN); + EXPECT(actual==Qualified("Vector",Qualified::EIGEN)); actual.clear(); // a basic type EXPECT(parse("double", type_g, space_p).full); - EXPECT(actual.name=="double"); - EXPECT(actual.namespaces.empty()); - EXPECT(actual.category==Qualified::BASIS); + EXPECT(actual==Qualified("double",Qualified::BASIS)); actual.clear(); // void EXPECT(parse("void", type_g, space_p).full); - EXPECT(actual.name=="void"); - EXPECT(actual.namespaces.empty()); - EXPECT(actual.category==Qualified::VOID); + EXPECT(actual==Qualified("void",Qualified::VOID)); actual.clear(); } diff --git a/wrap/tests/testWrap.cpp b/wrap/tests/testWrap.cpp index c1f6f091e..8f8c1994c 100644 --- a/wrap/tests/testWrap.cpp +++ b/wrap/tests/testWrap.cpp @@ -48,9 +48,9 @@ static const std::string headerPath = "/not_really_a_real_path/borg/gtsam/wrap"; /* ************************************************************************* */ TEST( wrap, ArgumentList ) { ArgumentList args; - Argument arg1; arg1.type.name = "double"; arg1.name = "x"; - Argument arg2; arg2.type.name = "double"; arg2.name = "y"; - Argument arg3; arg3.type.name = "double"; arg3.name = "z"; + Argument arg1; arg1.type.name_ = "double"; arg1.name = "x"; + Argument arg2; arg2.type.name_ = "double"; arg2.name = "y"; + Argument arg3; arg3.type.name_ = "double"; arg3.name = "z"; args.push_back(arg1); args.push_back(arg2); args.push_back(arg3); @@ -88,9 +88,9 @@ TEST( wrap, Small ) { // check return types LONGS_EQUAL(1, module.classes.size()); Class cls = module.classes.front(); - EXPECT(assert_equal("Point2", cls.name)); + EXPECT(assert_equal("Point2", cls.name())); EXPECT(!cls.isVirtual); - EXPECT(cls.namespaces.empty()); + EXPECT(cls.namespaces().empty()); LONGS_EQUAL(3, cls.nrMethods()); LONGS_EQUAL(1, cls.static_methods.size()); @@ -103,7 +103,7 @@ TEST( wrap, Small ) { ReturnValue rv1 = m1.returnValue(0); EXPECT(!rv1.isPair); EXPECT(!rv1.type1.isPtr); - EXPECT(assert_equal("double", rv1.type1.name)); + EXPECT(assert_equal("double", rv1.type1.name())); EXPECT_LONGS_EQUAL(ReturnType::BASIS, rv1.type1.category); // Method 2 @@ -115,7 +115,7 @@ TEST( wrap, Small ) { ReturnValue rv2 = m2.returnValue(0); EXPECT(!rv2.isPair); EXPECT(!rv2.type1.isPtr); - EXPECT(assert_equal("Matrix", rv2.type1.name)); + EXPECT(assert_equal("Matrix", rv2.type1.name())); EXPECT_LONGS_EQUAL(ReturnType::EIGEN, rv2.type1.category); // Method 3 @@ -127,7 +127,7 @@ TEST( wrap, Small ) { ReturnValue rv3 = m3.returnValue(0); EXPECT(!rv3.isPair); EXPECT(!rv3.type1.isPtr); - EXPECT(assert_equal("Point2", rv3.type1.name)); + EXPECT(assert_equal("Point2", rv3.type1.name())); EXPECT_LONGS_EQUAL(ReturnType::CLASS, rv3.type1.category); // Static Method 1 @@ -139,7 +139,7 @@ TEST( wrap, Small ) { ReturnValue rv4 = sm1.returnValue(0); EXPECT(!rv4.isPair); EXPECT(!rv4.type1.isPtr); - EXPECT(assert_equal("Vector", rv4.type1.name)); + EXPECT(assert_equal("Vector", rv4.type1.name())); EXPECT_LONGS_EQUAL(ReturnType::EIGEN, rv4.type1.category); } @@ -182,7 +182,7 @@ TEST( wrap, Geometry ) { // }; Class cls = module.classes.at(0); - EXPECT(assert_equal("Point2", cls.name)); + EXPECT(assert_equal("Point2", cls.name())); EXPECT_LONGS_EQUAL(2, cls.constructor.nrOverloads()); EXPECT_LONGS_EQUAL(8, cls.nrMethods()); @@ -191,7 +191,7 @@ TEST( wrap, Geometry ) { CHECK(cls.exists("returnChar")); Method m1 = cls.method("returnChar"); LONGS_EQUAL(1, m1.nrOverloads()); - EXPECT(assert_equal("char", m1.returnValue(0).type1.name)); + EXPECT(assert_equal("char", m1.returnValue(0).type1.name())); EXPECT_LONGS_EQUAL(ReturnType::BASIS, m1.returnValue(0).type1.category); EXPECT(!m1.returnValue(0).isPair); EXPECT(assert_equal("returnChar", m1.name())); @@ -205,7 +205,7 @@ TEST( wrap, Geometry ) { CHECK(cls.exists("vectorConfusion")); Method m1 = cls.method("vectorConfusion"); LONGS_EQUAL(1, m1.nrOverloads()); - EXPECT(assert_equal("VectorNotEigen", m1.returnValue(0).type1.name)); + EXPECT(assert_equal("VectorNotEigen", m1.returnValue(0).type1.name())); EXPECT_LONGS_EQUAL(ReturnType::CLASS, m1.returnValue(0).type1.category); EXPECT(!m1.returnValue(0).isPair); EXPECT(assert_equal("vectorConfusion", m1.name())); @@ -215,7 +215,7 @@ TEST( wrap, Geometry ) { } EXPECT_LONGS_EQUAL(0, cls.static_methods.size()); - EXPECT_LONGS_EQUAL(1, cls.namespaces.size()); + EXPECT_LONGS_EQUAL(1, cls.namespaces().size()); #ifndef WRAP_DISABLE_SERIALIZE // check serialization flag @@ -227,11 +227,11 @@ TEST( wrap, Geometry ) { // check second class, Point3 { Class cls = module.classes.at(1); - EXPECT(assert_equal("Point3", cls.name)); + EXPECT(assert_equal("Point3", cls.name())); EXPECT_LONGS_EQUAL(1, cls.constructor.nrOverloads()); EXPECT_LONGS_EQUAL(1, cls.nrMethods()); EXPECT_LONGS_EQUAL(2, cls.static_methods.size()); - EXPECT_LONGS_EQUAL(1, cls.namespaces.size()); + EXPECT_LONGS_EQUAL(1, cls.namespaces().size()); // first constructor takes 3 doubles ArgumentList c1 = cls.constructor.argumentList(0); @@ -240,7 +240,7 @@ TEST( wrap, Geometry ) { // check first double argument Argument a1 = c1.front(); EXPECT(!a1.is_const); - EXPECT(assert_equal("double", a1.type.name)); + EXPECT(assert_equal("double", a1.type.name_)); EXPECT(!a1.is_ref); EXPECT(assert_equal("x", a1.name)); @@ -248,7 +248,7 @@ TEST( wrap, Geometry ) { CHECK(cls.exists("norm")); Method m1 = cls.method("norm"); LONGS_EQUAL(1, m1.nrOverloads()); - EXPECT(assert_equal("double", m1.returnValue(0).type1.name)); + EXPECT(assert_equal("double", m1.returnValue(0).type1.name())); EXPECT_LONGS_EQUAL(ReturnType::BASIS, m1.returnValue(0).type1.category); EXPECT(assert_equal("norm", m1.name())); LONGS_EQUAL(1, m1.nrOverloads()); @@ -268,7 +268,7 @@ TEST( wrap, Geometry ) { EXPECT_LONGS_EQUAL( 2, testCls.constructor.nrOverloads()); EXPECT_LONGS_EQUAL(19, testCls.nrMethods()); EXPECT_LONGS_EQUAL( 0, testCls.static_methods.size()); - EXPECT_LONGS_EQUAL( 0, testCls.namespaces.size()); + EXPECT_LONGS_EQUAL( 0, testCls.namespaces().size()); // function to parse: pair return_pair (Vector v, Matrix A) const; CHECK(testCls.exists("return_pair")); @@ -276,9 +276,9 @@ TEST( wrap, Geometry ) { LONGS_EQUAL(1, m2.nrOverloads()); EXPECT(m2.returnValue(0).isPair); EXPECT_LONGS_EQUAL(ReturnType::EIGEN, m2.returnValue(0).type1.category); - EXPECT(assert_equal("Vector", m2.returnValue(0).type1.name)); + EXPECT(assert_equal("Vector", m2.returnValue(0).type1.name())); EXPECT_LONGS_EQUAL(ReturnType::EIGEN, m2.returnValue(0).type2.category); - EXPECT(assert_equal("Matrix", m2.returnValue(0).type2.name)); + EXPECT(assert_equal("Matrix", m2.returnValue(0).type2.name())); // checking pointer args and return values // pair return_ptrs (Test* p1, Test* p2) const; @@ -292,17 +292,17 @@ TEST( wrap, Geometry ) { EXPECT(arg1.is_ptr); EXPECT(!arg1.is_const); EXPECT(!arg1.is_ref); - EXPECT(assert_equal("Test", arg1.type.name)); + EXPECT(assert_equal("Test", arg1.type.name_)); EXPECT(assert_equal("p1", arg1.name)); - EXPECT(arg1.type.namespaces.empty()); + EXPECT(arg1.type.namespaces_.empty()); Argument arg2 = args.at(1); EXPECT(arg2.is_ptr); EXPECT(!arg2.is_const); EXPECT(!arg2.is_ref); - EXPECT(assert_equal("Test", arg2.type.name)); + EXPECT(assert_equal("Test", arg2.type.name_)); EXPECT(assert_equal("p2", arg2.name)); - EXPECT(arg2.type.namespaces.empty()); + EXPECT(arg2.type.namespaces_.empty()); } // evaluate global functions @@ -313,10 +313,10 @@ TEST( wrap, Geometry ) { GlobalFunction gfunc = module.global_functions.at("aGlobalFunction"); EXPECT(assert_equal("aGlobalFunction", gfunc.name())); LONGS_EQUAL(1, gfunc.nrOverloads()); - EXPECT(assert_equal("Vector", gfunc.returnValue(0).type1.name)); + EXPECT(assert_equal("Vector", gfunc.returnValue(0).type1.name())); EXPECT_LONGS_EQUAL(1, gfunc.nrOverloads()); LONGS_EQUAL(1, gfunc.overloads.size()); - EXPECT(gfunc.overloads.front().namespaces.empty()); + EXPECT(gfunc.overloads.front().namespaces().empty()); } } @@ -338,44 +338,44 @@ TEST( wrap, parse_namespaces ) { { Class cls = module.classes.at(0); - EXPECT(assert_equal("ClassA", cls.name)); + EXPECT(assert_equal("ClassA", cls.name())); strvec exp_namespaces; exp_namespaces += "ns1"; - EXPECT(assert_equal(exp_namespaces, cls.namespaces)); + EXPECT(assert_equal(exp_namespaces, cls.namespaces())); } { Class cls = module.classes.at(1); - EXPECT(assert_equal("ClassB", cls.name)); + EXPECT(assert_equal("ClassB", cls.name())); strvec exp_namespaces; exp_namespaces += "ns1"; - EXPECT(assert_equal(exp_namespaces, cls.namespaces)); + EXPECT(assert_equal(exp_namespaces, cls.namespaces())); } { Class cls = module.classes.at(2); - EXPECT(assert_equal("ClassA", cls.name)); + EXPECT(assert_equal("ClassA", cls.name())); strvec exp_namespaces; exp_namespaces += "ns2"; - EXPECT(assert_equal(exp_namespaces, cls.namespaces)); + EXPECT(assert_equal(exp_namespaces, cls.namespaces())); } { Class cls = module.classes.at(3); - EXPECT(assert_equal("ClassB", cls.name)); + EXPECT(assert_equal("ClassB", cls.name())); strvec exp_namespaces; exp_namespaces += "ns2", "ns3"; - EXPECT(assert_equal(exp_namespaces, cls.namespaces)); + EXPECT(assert_equal(exp_namespaces, cls.namespaces())); } { Class cls = module.classes.at(4); - EXPECT(assert_equal("ClassC", cls.name)); + EXPECT(assert_equal("ClassC", cls.name())); strvec exp_namespaces; exp_namespaces += "ns2"; - EXPECT(assert_equal(exp_namespaces, cls.namespaces)); + EXPECT(assert_equal(exp_namespaces, cls.namespaces())); } { Class cls = module.classes.at(5); - EXPECT(assert_equal("ClassD", cls.name)); + EXPECT(assert_equal("ClassD", cls.name())); strvec exp_namespaces; - EXPECT(assert_equal(exp_namespaces, cls.namespaces)); + EXPECT(assert_equal(exp_namespaces, cls.namespaces())); } // evaluate global functions @@ -387,15 +387,15 @@ TEST( wrap, parse_namespaces ) { GlobalFunction gfunc = module.global_functions.at("aGlobalFunction"); EXPECT(assert_equal("aGlobalFunction", gfunc.name())); LONGS_EQUAL(2, gfunc.nrOverloads()); - EXPECT(assert_equal("Vector", gfunc.returnValue(0).type1.name)); + EXPECT(assert_equal("Vector", gfunc.returnValue(0).type1.name())); // check namespaces LONGS_EQUAL(2, gfunc.overloads.size()); strvec exp_namespaces1; exp_namespaces1 += "ns1"; - EXPECT(assert_equal(exp_namespaces1, gfunc.overloads.at(0).namespaces)); + EXPECT(assert_equal(exp_namespaces1, gfunc.overloads.at(0).namespaces())); strvec exp_namespaces2; exp_namespaces2 += "ns2"; - EXPECT(assert_equal(exp_namespaces2, gfunc.overloads.at(1).namespaces)); + EXPECT(assert_equal(exp_namespaces2, gfunc.overloads.at(1).namespaces())); } } From 24f5636d6a853d4a54dc6db083bd7ccc80e9c14f Mon Sep 17 00:00:00 2001 From: dellaert Date: Sun, 30 Nov 2014 20:25:26 +0100 Subject: [PATCH 049/126] Moved to header --- wrap/Argument.h | 94 ++++++++++++++++++++++++++++++++++++- wrap/tests/testArgument.cpp | 90 ----------------------------------- 2 files changed, 93 insertions(+), 91 deletions(-) diff --git a/wrap/Argument.h b/wrap/Argument.h index 2a3e4b18b..c49075932 100644 --- a/wrap/Argument.h +++ b/wrap/Argument.h @@ -124,5 +124,97 @@ struct ArgumentList: public std::vector { }; -} // \namespace wrap +static const bool T = true; + +/* ************************************************************************* */ +// http://boost-spirit.com/distrib/spirit_1_8_2/libs/spirit/doc/grammar.html +struct ArgumentGrammar: public classic::grammar { + + wrap::Argument& result_; ///< successful parse will be placed in here + TypeGrammar argument_type_g; + + /// Construct type grammar and specify where result is placed + ArgumentGrammar(wrap::Argument& result) : + result_(result), argument_type_g(result.type) { + } + + /// Definition of type grammar + template + struct definition: basic_rules { + + typedef classic::rule Rule; + + Rule argument_p, argumentList_p; + + definition(ArgumentGrammar const& self) { + + using namespace wrap; + using namespace classic; + + // NOTE: allows for pointers to all types + // Slightly more permissive than before on basis/eigen type qualification + // Also, currently parses Point2*&, can't make it work otherwise :-( + argument_p = !str_p("const")[assign_a(self.result_.is_const, T)] // + >> self.argument_type_g // + >> !ch_p('*')[assign_a(self.result_.is_ptr, T)] + >> !ch_p('&')[assign_a(self.result_.is_ref, T)] + >> basic_rules::name_p[assign_a(self.result_.name)]; + } + + Rule const& start() const { + return argument_p; + } + + }; +}; +// ArgumentGrammar + +/* ************************************************************************* */ +// http://boost-spirit.com/distrib/spirit_1_8_2/libs/spirit/doc/grammar.html +struct ArgumentListGrammar: public classic::grammar { + + wrap::ArgumentList& result_; ///< successful parse will be placed in here + + Argument arg0, arg; + ArgumentGrammar argument_g; + + /// Construct type grammar and specify where result is placed + ArgumentListGrammar(wrap::ArgumentList& result) : + result_(result), argument_g(arg) { + } + + /// Definition of type grammar + template + struct definition: basic_rules { + + typedef classic::rule Rule; + + Rule argument_p, argumentList_p; + + definition(ArgumentListGrammar const& self) { + + using namespace wrap; + using namespace classic; + + // NOTE: allows for pointers to all types + // Slightly more permissive than before on basis/eigen type qualification + argument_p = self.argument_g // + [push_back_a(self.result_, self.arg)] // +// [assign_a(self.arg, self.arg0)] + ; + + argumentList_p = '(' >> !argument_p >> *(',' >> argument_p) >> ')'; + } + + Rule const& start() const { + return argumentList_p; + } + + }; +}; +// ArgumentListGrammar + +/* ************************************************************************* */ + +}// \namespace wrap diff --git a/wrap/tests/testArgument.cpp b/wrap/tests/testArgument.cpp index 8a50d694f..31269c652 100644 --- a/wrap/tests/testArgument.cpp +++ b/wrap/tests/testArgument.cpp @@ -23,51 +23,6 @@ using namespace std; using namespace wrap; -static const bool T = true; - -/* ************************************************************************* */ -// http://boost-spirit.com/distrib/spirit_1_8_2/libs/spirit/doc/grammar.html -struct ArgumentGrammar: public classic::grammar { - - wrap::Argument& result_; ///< successful parse will be placed in here - TypeGrammar argument_type_g; - - /// Construct type grammar and specify where result is placed - ArgumentGrammar(wrap::Argument& result) : - result_(result), argument_type_g(result.type) { - } - - /// Definition of type grammar - template - struct definition: basic_rules { - - typedef classic::rule Rule; - - Rule argument_p, argumentList_p; - - definition(ArgumentGrammar const& self) { - - using namespace wrap; - using namespace classic; - - // NOTE: allows for pointers to all types - // Slightly more permissive than before on basis/eigen type qualification - // Also, currently parses Point2*&, can't make it work otherwise :-( - argument_p = !str_p("const")[assign_a(self.result_.is_const, T)] // - >> self.argument_type_g // - >> !ch_p('*')[assign_a(self.result_.is_ptr, T)] - >> !ch_p('&')[assign_a(self.result_.is_ref, T)] - >> basic_rules::name_p[assign_a(self.result_.name)]; - } - - Rule const& start() const { - return argument_p; - } - - }; -}; -// ArgumentGrammar - //****************************************************************************** TEST( Argument, grammar ) { @@ -122,51 +77,6 @@ TEST( Argument, grammar ) { actual = arg0; } -/* ************************************************************************* */ -// http://boost-spirit.com/distrib/spirit_1_8_2/libs/spirit/doc/grammar.html -struct ArgumentListGrammar: public classic::grammar { - - wrap::ArgumentList& result_; ///< successful parse will be placed in here - - Argument arg0, arg; - ArgumentGrammar argument_g; - - /// Construct type grammar and specify where result is placed - ArgumentListGrammar(wrap::ArgumentList& result) : - result_(result), argument_g(arg) { - } - - /// Definition of type grammar - template - struct definition: basic_rules { - - typedef classic::rule Rule; - - Rule argument_p, argumentList_p; - - definition(ArgumentListGrammar const& self) { - - using namespace wrap; - using namespace classic; - - // NOTE: allows for pointers to all types - // Slightly more permissive than before on basis/eigen type qualification - argument_p = self.argument_g // - [push_back_a(self.result_, self.arg)] // -// [assign_a(self.arg, self.arg0)] - ; - - argumentList_p = '(' >> !argument_p >> *(',' >> argument_p) >> ')'; - } - - Rule const& start() const { - return argumentList_p; - } - - }; -}; -// ArgumentListGrammar - //****************************************************************************** TEST( ArgumentList, grammar ) { From 5bcd5d3c89ac1af73b4c3071401fce414083e873 Mon Sep 17 00:00:00 2001 From: dellaert Date: Sun, 30 Nov 2014 20:46:19 +0100 Subject: [PATCH 050/126] Commented out grammar --- wrap/tests/testMethod.cpp | 186 +++++++++++++++++++------------------- 1 file changed, 91 insertions(+), 95 deletions(-) diff --git a/wrap/tests/testMethod.cpp b/wrap/tests/testMethod.cpp index b94bd8f9f..bc21b332c 100644 --- a/wrap/tests/testMethod.cpp +++ b/wrap/tests/testMethod.cpp @@ -23,13 +23,13 @@ using namespace std; using namespace wrap; -/* ************************************************************************* */ +//****************************************************************************** // Constructor TEST( Method, Constructor ) { Method method; } -/* ************************************************************************* */ +//****************************************************************************** // addOverload TEST( Method, addOverload ) { Method method; @@ -42,105 +42,101 @@ TEST( Method, addOverload ) { EXPECT_LONGS_EQUAL(2, method.nrOverloads()); } -// http://boost-spirit.com/distrib/spirit_1_8_2/libs/spirit/doc/grammar.html -struct method_grammar: public classic::grammar { - - wrap::Method& result_; ///< successful parse will be placed in here - - ArgumentList args; - Argument arg0, arg; - TypeGrammar argument_type_g; - - ReturnType retType0, retType; - TypeGrammar returntype_g; - - ReturnValue retVal0, retVal; - - /// Construct type grammar and specify where result is placed - method_grammar(wrap::Method& result) : - result_(result), argument_type_g(arg.type), returntype_g(retType) { - } - - /// Definition of type grammar - template - struct definition: basic_rules { - - typedef classic::rule Rule; - - Rule templateArgValue_p, templateArgValues_p, argument_p, argumentList_p, - returnType1_p, returnType2_p, pair_p, returnValue_p, methodName_p, - method_p; - - definition(method_grammar const& self) { - - using namespace wrap; - using namespace classic; - -// Rule templateArgValue_p = type_grammar(self.templateArgValue); +//// http://boost-spirit.com/distrib/spirit_1_8_2/libs/spirit/doc/grammar.html +//struct method_grammar: public classic::grammar { // -// // template -// Rule templateArgValues_p = (str_p("template") >> '<' >> name_p >> '=' -// >> '{' >> !(templateArgValue_p >> *(',' >> templateArgValue_p)) >> '}' -// >> '>'); +// wrap::Method& result_; ///< successful parse will be placed in here // - // NOTE: allows for pointers to all types - // Slightly more permissive than before on basis/eigen type qualification - argument_p = // - !str_p("const")[assign_a(self.arg.is_const, true)] // - >> self.argument_type_g // - >> (!ch_p('&')[assign_a(self.arg.is_ref, true)] - | !ch_p('*')[assign_a(self.arg.is_ptr, true)]) // - [push_back_a(self.args, self.arg)] // - [assign_a(self.arg, self.arg0)]; - - argumentList_p = !argument_p >> *(',' >> argument_p); +// ArgumentList args; +// Argument arg0, arg; +// TypeGrammar argument_type_g; // - returnType1_p = self.returntype_g // - [assign_a(self.retVal.type1, retType)] // - [assign_a(self.retType, self.retType0)]; - - returnType2_p = self.returntype_g // - [assign_a(self.retVal.type2, retType)] // - [assign_a(self.retType, self.retType0)]; - - pair_p = (str_p("pair") >> '<' >> returnType1_p >> ',' >> returnType2_p - >> '>')[assign_a(self.retVal.isPair, true)]; - - returnValue_p = pair_p | returnType1_p; - - methodName_p = lexeme_d[(upper_p | lower_p) >> *(alnum_p | '_')]; - - // gtsam::Values retract(const gtsam::VectorValues& delta) const; - method_p = -// !templateArgValues_p >> - (returnValue_p >> methodName_p >> '(' >> argumentList_p >> ')' - >> !str_p("const") >> ';' >> *basic_rules::comments_p); - } - - Rule const& start() const { - return method_p; - } - - }; -}; -// method_grammar +// ReturnType retType0, retType; +// TypeGrammar returntype_g; +// +// ReturnValue retVal0, retVal; +// +// /// Construct type grammar and specify where result is placed +// method_grammar(wrap::Method& result) : +// result_(result), argument_type_g(arg.type), returntype_g(retType) { +// } +// +// /// Definition of type grammar +// template +// struct definition: basic_rules { +// +// typedef classic::rule Rule; +// +// Rule templateArgValue_p, templateArgValues_p, argument_p, argumentList_p, +// returnType1_p, returnType2_p, pair_p, returnValue_p, methodName_p, +// method_p; +// +// definition(method_grammar const& self) { +// +// using namespace wrap; +// using namespace classic; +// +//// Rule templateArgValue_p = type_grammar(self.templateArgValue); +//// +//// // template +//// Rule templateArgValues_p = (str_p("template") >> '<' >> name_p >> '=' +//// >> '{' >> !(templateArgValue_p >> *(',' >> templateArgValue_p)) >> '}' +//// >> '>'); +//// +// // Create type grammar that will place result in actual +// ArgumentList actual; +// ArgumentListGrammar g(actual); +// +// EXPECT(parse("(const gtsam::Point2& p4)", g, space_p).full); +// EXPECT_LONGS_EQUAL(1, actual.size()); +// actual.clear(); +// +// returnType1_p = self.returntype_g // +// [assign_a(self.retVal.type1, retType)] // +// [assign_a(self.retType, self.retType0)]; +// +// returnType2_p = self.returntype_g // +// [assign_a(self.retVal.type2, retType)] // +// [assign_a(self.retType, self.retType0)]; +// +// pair_p = (str_p("pair") >> '<' >> returnType1_p >> ',' >> returnType2_p +// >> '>')[assign_a(self.retVal.isPair, true)]; +// +// returnValue_p = pair_p | returnType1_p; +// +// methodName_p = lexeme_d[(upper_p | lower_p) >> *(alnum_p | '_')]; +// +// // gtsam::Values retract(const gtsam::VectorValues& delta) const; +// method_p = +//// !templateArgValues_p >> +// (returnValue_p >> methodName_p >> '(' >> argumentList_p >> ')' +// >> !str_p("const") >> ';' >> *basic_rules::comments_p); +// } +// +// Rule const& start() const { +// return method_p; +// } +// +// }; +//}; +//// method_grammar +// +////****************************************************************************** +//TEST( Method, grammar ) { +// +// using classic::space_p; +// +// // Create type grammar that will place result in actual +// Method actual; +// method_grammar method_g(actual); +// +// // a class type with namespaces +// EXPECT(parse("double x() const;", method_g, space_p).full); +//} //****************************************************************************** -TEST( Method, grammar ) { - - using classic::space_p; - - // Create type grammar that will place result in actual - Method actual; - method_grammar method_g(actual); - - // a class type with namespaces - EXPECT(parse("double x() const;", method_g, space_p).full); -} - -/* ************************************************************************* */ int main() { TestResult tr; return TestRegistry::runAllTests(tr); } -/* ************************************************************************* */ +//****************************************************************************** From 0dcd102f5e3c4ba9b027cd3272916e21d383ae6b Mon Sep 17 00:00:00 2001 From: dellaert Date: Sun, 30 Nov 2014 20:46:47 +0100 Subject: [PATCH 051/126] Saving before restoring --- wrap/Module.cpp | 25 ++--- wrap/tests/geometry.h | 242 +++++++++++++++++++++--------------------- 2 files changed, 127 insertions(+), 140 deletions(-) diff --git a/wrap/Module.cpp b/wrap/Module.cpp index 90fabda8a..21c5262da 100644 --- a/wrap/Module.cpp +++ b/wrap/Module.cpp @@ -152,24 +152,14 @@ void Module::parseMarkup(const std::string& data) { '<' >> basic.name_p[push_back_a(cls.templateArgs)] >> *(',' >> basic.name_p[push_back_a(cls.templateArgs)]) >> '>'); - // NOTE: allows for pointers to all types - // Slightly more permissive than before on basis/eigen type qualification + // Argument list ArgumentList args; - Argument arg0, arg; - TypeGrammar argument_type_g(arg.type); - Rule argument_p = - !str_p("const")[assign_a(arg.is_const, true)] - >> argument_type_g - >> (!ch_p('&')[assign_a(arg.is_ref, true)] | !ch_p('*')[assign_a(arg.is_ptr, true)]) - [push_back_a(args, arg)] - [assign_a(arg,arg0)]; - - Rule argumentList_p = !argument_p >> * (',' >> argument_p); + ArgumentListGrammar argumentlist_g(args); // parse class constructor Constructor constructor0(verbose), constructor(verbose); Rule constructor_p = - (basic.className_p >> '(' >> argumentList_p >> ')' >> ';' >> !basic.comments_p) + (basic.className_p >> '(' >> argumentlist_g >> ')' >> ';' >> !basic.comments_p) [bl::bind(&Constructor::push_back, bl::var(constructor), bl::var(args))] [clear_a(args)]; @@ -194,7 +184,7 @@ void Module::parseMarkup(const std::string& data) { Rule method_p = !templateArgValues_p >> (returnValue_p >> methodName_p[assign_a(methodName)] >> - '(' >> argumentList_p >> ')' >> + '(' >> argumentlist_g >> ')' >> !str_p("const")[assign_a(isConst,true)] >> ';' >> *basic.comments_p) [bl::bind(&Class::addMethod, bl::var(cls), verbose, bl::var(isConst), bl::var(methodName), bl::var(args), bl::var(retVal), @@ -208,7 +198,7 @@ void Module::parseMarkup(const std::string& data) { Rule static_method_p = (str_p("static") >> returnValue_p >> staticMethodName_p[assign_a(methodName)] >> - '(' >> argumentList_p >> ')' >> ';' >> *basic.comments_p) + '(' >> argumentlist_g >> ')' >> ';' >> *basic.comments_p) [bl::bind(&StaticMethod::addOverload, bl::var(cls.static_methods)[bl::var(methodName)], bl::var(methodName), bl::var(args), bl::var(retVal), Qualified(),verbose)] @@ -248,7 +238,7 @@ void Module::parseMarkup(const std::string& data) { Qualified globalFunction; Rule global_function_p = (returnValue_p >> staticMethodName_p[assign_a(globalFunction.name_)] >> - '(' >> argumentList_p >> ')' >> ';' >> *basic.comments_p) + '(' >> argumentlist_g >> ')' >> ';' >> *basic.comments_p) [assign_a(globalFunction.namespaces_,namespaces)] [bl::bind(&GlobalFunction::addOverload, bl::var(global_functions)[bl::var(globalFunction.name_)], @@ -323,8 +313,7 @@ void Module::parseMarkup(const std::string& data) { printf("parsing stopped at \n%.20s\n",info.stop); cout << "Stopped near:\n" "class '" << cls.name() << "'\n" - "method '" << methodName << "'\n" - "argument '" << arg.name << "'" << endl; + "method '" << methodName << endl; throw ParseFailed((int)info.length); } diff --git a/wrap/tests/geometry.h b/wrap/tests/geometry.h index 0675490f9..d40bf0475 100644 --- a/wrap/tests/geometry.h +++ b/wrap/tests/geometry.h @@ -1,4 +1,4 @@ - // comments! +// comments! class VectorNotEigen; class ns::OtherClass; @@ -7,128 +7,126 @@ namespace gtsam { class Point2 { Point2(); -// Point2(double x, double y); + 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(); -// -// void serializable() const; // Sets flag and creates export, but does not make serialization functions + 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(); + + void serializable() const; // Sets flag and creates export, but does not make serialization functions }; -} // end namespace should be removed +class Point3 { + Point3(double x, double y, double z); + double norm() const; -//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 -//}; -// -//} -//// 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(); -// -// pair return_pair (Vector v, Matrix A) const; // intentionally the first method -// -// 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(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! -//}; -// -// -//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 -// void 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; -//}; -// -//// 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; -// -//// comments at the end! -// -//// even more comments at the end! + // 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 +}; + +} +// 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(); + + pair return_pair (Vector v, Matrix A) const; // intentionally the first method + + 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(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! +}; + + +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 + void 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; +}; + +// 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; + +// comments at the end! + +// even more comments at the end! From 294c7bd53bae62c0f167432efb64494ff2c8c57e Mon Sep 17 00:00:00 2001 From: dellaert Date: Sun, 30 Nov 2014 21:54:10 +0100 Subject: [PATCH 052/126] Commented out strict match to make work - revisit ! --- wrap/Qualified.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/wrap/Qualified.h b/wrap/Qualified.h index 72d1b1c4f..50805ec50 100644 --- a/wrap/Qualified.h +++ b/wrap/Qualified.h @@ -84,7 +84,7 @@ public: // Qualified is 'abused' as template argument name as well // this function checks whether *this matches with templateArg bool match(const std::string& templateArg) const { - return (name_ == templateArg && namespaces_.empty() && category == CLASS); + return (name_ == templateArg && namespaces_.empty());//TODO && category == CLASS); } void rename(const Qualified& q) { @@ -220,7 +220,7 @@ public: [assign_a(self.result_.name_)] // [assign_a(self.result_.category, CLASS)]; - type_p = void_p | my_basisType_p | my_eigenType_p | class_p; + type_p = void_p | my_basisType_p | class_p | my_eigenType_p; } Rule const& start() const { From 303b051cd1f256e982fb2c050afece0f95547805 Mon Sep 17 00:00:00 2001 From: dellaert Date: Sun, 30 Nov 2014 21:54:24 +0100 Subject: [PATCH 053/126] Original file restored --- wrap/tests/geometry.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/wrap/tests/geometry.h b/wrap/tests/geometry.h index d40bf0475..3fec21ab9 100644 --- a/wrap/tests/geometry.h +++ b/wrap/tests/geometry.h @@ -1,4 +1,4 @@ -// comments! + // comments! class VectorNotEigen; class ns::OtherClass; From bba78e48e4d21983f60c3aa5c4bd3fff8a70e515 Mon Sep 17 00:00:00 2001 From: dellaert Date: Sun, 30 Nov 2014 21:54:56 +0100 Subject: [PATCH 054/126] test VectorEigen --- wrap/tests/testType.cpp | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/wrap/tests/testType.cpp b/wrap/tests/testType.cpp index 45ffdb6de..f61e81c62 100644 --- a/wrap/tests/testType.cpp +++ b/wrap/tests/testType.cpp @@ -46,6 +46,11 @@ TEST( Type, grammar ) { EXPECT(actual==Qualified("Point2",Qualified::CLASS)); actual.clear(); + // a class type with no namespaces + EXPECT(parse("VectorNotEigen", type_g, space_p).full); + EXPECT(actual==Qualified("VectorNotEigen",Qualified::CLASS)); + actual.clear(); + // an Eigen type EXPECT(parse("Vector", type_g, space_p).full); EXPECT(actual==Qualified("Vector",Qualified::EIGEN)); From 58806b75d23f663e5a791148fe0439508890aaf5 Mon Sep 17 00:00:00 2001 From: dellaert Date: Sun, 30 Nov 2014 22:33:30 +0100 Subject: [PATCH 055/126] testReturnValue with prototype grammar --- .cproject | 8 +++ wrap/Argument.h | 15 ++---- wrap/Qualified.h | 6 ++- wrap/ReturnType.h | 16 ++++-- wrap/ReturnValue.h | 16 ++++++ wrap/tests/testReturnValue.cpp | 89 ++++++++++++++++++++++++++++++++++ 6 files changed, 132 insertions(+), 18 deletions(-) create mode 100644 wrap/tests/testReturnValue.cpp diff --git a/.cproject b/.cproject index cbe6f0b56..b0eb31888 100644 --- a/.cproject +++ b/.cproject @@ -2409,6 +2409,14 @@ true true + + make + -j4 + testReturnValue.run + true + true + true + make -j5 diff --git a/wrap/Argument.h b/wrap/Argument.h index c49075932..367d494c9 100644 --- a/wrap/Argument.h +++ b/wrap/Argument.h @@ -124,8 +124,6 @@ struct ArgumentList: public std::vector { }; -static const bool T = true; - /* ************************************************************************* */ // http://boost-spirit.com/distrib/spirit_1_8_2/libs/spirit/doc/grammar.html struct ArgumentGrammar: public classic::grammar { @@ -175,7 +173,7 @@ struct ArgumentListGrammar: public classic::grammar { wrap::ArgumentList& result_; ///< successful parse will be placed in here - Argument arg0, arg; + Argument arg, arg0; ArgumentGrammar argument_g; /// Construct type grammar and specify where result is placed @@ -192,17 +190,10 @@ struct ArgumentListGrammar: public classic::grammar { Rule argument_p, argumentList_p; definition(ArgumentListGrammar const& self) { - - using namespace wrap; using namespace classic; - - // NOTE: allows for pointers to all types - // Slightly more permissive than before on basis/eigen type qualification argument_p = self.argument_g // - [push_back_a(self.result_, self.arg)] // -// [assign_a(self.arg, self.arg0)] - ; - + [classic::push_back_a(self.result_, self.arg)] // + [assign_a(self.arg, self.arg0)]; argumentList_p = '(' >> !argument_p >> *(',' >> argument_p) >> ')'; } diff --git a/wrap/Qualified.h b/wrap/Qualified.h index 50805ec50..7f707319d 100644 --- a/wrap/Qualified.h +++ b/wrap/Qualified.h @@ -106,7 +106,7 @@ public: return namespaces_.empty() && name_.empty(); } - void clear() { + virtual void clear() { namespaces_.clear(); name_.clear(); category = VOID; @@ -231,5 +231,9 @@ public: }; // type_grammar +// Needed for other parsers in Argument.h and ReturnType.h +static const bool T = true; + + }// \namespace wrap diff --git a/wrap/ReturnType.h b/wrap/ReturnType.h index e619a18d1..5301e71a6 100644 --- a/wrap/ReturnType.h +++ b/wrap/ReturnType.h @@ -22,13 +22,19 @@ struct ReturnType: Qualified { bool isPtr; /// Makes a void type - ReturnType() : - isPtr(false) { + ReturnType(bool ptr = false) : + isPtr(ptr) { } - /// Make a Class type, no namespaces - ReturnType(const std::string& name) : - Qualified(name,Qualified::CLASS), isPtr(false) { + /// Constructor, no namespaces + ReturnType(const std::string& name, Qualified::Category c = Qualified::CLASS, + bool ptr = false) : + Qualified(name, c), isPtr(ptr) { + } + + virtual void clear() { + Qualified::clear(); + isPtr = false; } /// Check if this type is in a set of valid types diff --git a/wrap/ReturnValue.h b/wrap/ReturnValue.h index abfcec2b0..1ab844043 100644 --- a/wrap/ReturnValue.h +++ b/wrap/ReturnValue.h @@ -35,6 +35,22 @@ struct ReturnValue { isPair(false), type1(type) { } + /// Constructor + ReturnValue(const ReturnType& t1, const ReturnType& t2) : + isPair(true), type1(t1), type2(t2) { + } + + virtual void clear() { + type1.clear(); + type2.clear(); + isPair = false; + } + + bool operator==(const ReturnValue& other) const { + return isPair == other.isPair && type1 == other.type1 + && type2 == other.type2; + } + /// Substitute template argument ReturnValue expandTemplate(const TemplateSubstitution& ts) const; diff --git a/wrap/tests/testReturnValue.cpp b/wrap/tests/testReturnValue.cpp new file mode 100644 index 000000000..be245e75e --- /dev/null +++ b/wrap/tests/testReturnValue.cpp @@ -0,0 +1,89 @@ +/* ---------------------------------------------------------------------------- + + * GTSAM Copyright 2010, Georgia Tech Research Corporation, + * Atlanta, Georgia 30332-0415 + * All Rights Reserved + * Authors: Frank Dellaert, et al. (see THANKS for the full author list) + + * See LICENSE for the license information + + * -------------------------------------------------------------------------- */ + +/** + * @file testReturnValue.cpp + * @brief Unit test for ReturnValue class & parser + * @author Frank Dellaert + * @date Nov 30, 2014 + **/ + +#include +#include +#include + +using namespace std; +using namespace wrap; + +//****************************************************************************** +// http://boost-spirit.com/distrib/spirit_1_8_2/libs/spirit/doc/grammar.html +struct ReturnValueGrammar: public classic::grammar { + + wrap::ReturnValue& result_; ///< successful parse will be placed in here + + TypeGrammar returnType1_g, returnType2_g; + + /// Construct type grammar and specify where result is placed + ReturnValueGrammar(wrap::ReturnValue& result) : + result_(result), returnType1_g(result.type1), returnType2_g(result.type2) { + } + + /// Definition of type grammar + template + struct definition: basic_rules { + + typedef classic::rule Rule; + + Rule pair_p, returnValue_p; + + definition(ReturnValueGrammar const& self) { + + using namespace wrap; + using namespace classic; + + pair_p = (str_p("pair") >> '<' >> self.returnType1_g >> ',' + >> self.returnType2_g >> '>')[assign_a(self.result_.isPair, T)]; + + returnValue_p = pair_p | self.returnType1_g; + } + + Rule const& start() const { + return returnValue_p; + } + + }; +}; +// ReturnValueGrammar + +//****************************************************************************** +TEST( ReturnValue, grammar ) { + + using classic::space_p; + + // Create type grammar that will place result in actual + ReturnValue actual; + ReturnValueGrammar g(actual); + + EXPECT(parse("VectorNotEigen", g, space_p).full); + EXPECT(actual==ReturnValue(ReturnType("VectorNotEigen",Qualified::CLASS))); + actual.clear(); + + EXPECT(parse("double", g, space_p).full); + EXPECT(actual==ReturnValue(ReturnType("double",Qualified::BASIS))); + actual.clear(); +} + +//****************************************************************************** +int main() { + TestResult tr; + return TestRegistry::runAllTests(tr); +} +//****************************************************************************** From dc42773f1e952d4ba588fee5e7c0feba99924c89 Mon Sep 17 00:00:00 2001 From: dellaert Date: Sun, 30 Nov 2014 23:02:23 +0100 Subject: [PATCH 056/126] Some more tests --- wrap/ReturnType.h | 10 ++++---- wrap/tests/testReturnValue.cpp | 42 ++++++++++++++++++++++++++++------ wrap/tests/testType.cpp | 16 +++++++++++++ 3 files changed, 56 insertions(+), 12 deletions(-) diff --git a/wrap/ReturnType.h b/wrap/ReturnType.h index 5301e71a6..64ef26991 100644 --- a/wrap/ReturnType.h +++ b/wrap/ReturnType.h @@ -9,6 +9,7 @@ #include "FileWriter.h" #include "TypeAttributesTable.h" #include "utilities.h" +#include #pragma once @@ -17,18 +18,17 @@ namespace wrap { /** * Encapsulates return value of a method or function */ -struct ReturnType: Qualified { +struct ReturnType: public Qualified { bool isPtr; /// Makes a void type - ReturnType(bool ptr = false) : - isPtr(ptr) { + ReturnType() : + isPtr(false) { } /// Constructor, no namespaces - ReturnType(const std::string& name, Qualified::Category c = Qualified::CLASS, - bool ptr = false) : + ReturnType(const std::string& name, Category c = CLASS, bool ptr = false) : Qualified(name, c), isPtr(ptr) { } diff --git a/wrap/tests/testReturnValue.cpp b/wrap/tests/testReturnValue.cpp index be245e75e..3cd7e63ca 100644 --- a/wrap/tests/testReturnValue.cpp +++ b/wrap/tests/testReturnValue.cpp @@ -23,6 +23,32 @@ using namespace std; using namespace wrap; +//****************************************************************************** +TEST( ReturnType, Constructor1 ) { + ReturnType actual("Point2"); + EXPECT(actual.namespaces().empty()); + EXPECT(actual.name()=="Point2"); + EXPECT(actual.category==Qualified::CLASS); + EXPECT(!actual.isPtr); +} + +//****************************************************************************** +TEST( ReturnType, Constructor2 ) { + ReturnType actual("Point3",Qualified::CLASS, true); + EXPECT(actual.namespaces().empty()); + EXPECT(actual.name()=="Point3"); + EXPECT(actual.category==Qualified::CLASS); + EXPECT(actual.isPtr); +} + +//****************************************************************************** +TEST( ReturnValue, Constructor ) { + ReturnValue actual(ReturnType("Point2"), ReturnType("Point3")); + EXPECT(actual.type1==Qualified("Point2")); + EXPECT(actual.type2==Qualified("Point3")); + EXPECT(actual.isPair); +} + //****************************************************************************** // http://boost-spirit.com/distrib/spirit_1_8_2/libs/spirit/doc/grammar.html struct ReturnValueGrammar: public classic::grammar { @@ -38,15 +64,12 @@ struct ReturnValueGrammar: public classic::grammar { /// Definition of type grammar template - struct definition: basic_rules { + struct definition { - typedef classic::rule Rule; - - Rule pair_p, returnValue_p; + classic::rule pair_p, returnValue_p; definition(ReturnValueGrammar const& self) { - using namespace wrap; using namespace classic; pair_p = (str_p("pair") >> '<' >> self.returnType1_g >> ',' @@ -55,7 +78,7 @@ struct ReturnValueGrammar: public classic::grammar { returnValue_p = pair_p | self.returnType1_g; } - Rule const& start() const { + classic::rule const& start() const { return returnValue_p; } @@ -72,8 +95,13 @@ TEST( ReturnValue, grammar ) { ReturnValue actual; ReturnValueGrammar g(actual); + EXPECT(parse("pair", g, space_p).full); + EXPECT( actual==ReturnValue(ReturnType("Point2"),ReturnType("Point3"))); + cout << actual << endl; + actual.clear(); + EXPECT(parse("VectorNotEigen", g, space_p).full); - EXPECT(actual==ReturnValue(ReturnType("VectorNotEigen",Qualified::CLASS))); + EXPECT(actual==ReturnValue(ReturnType("VectorNotEigen"))); actual.clear(); EXPECT(parse("double", g, space_p).full); diff --git a/wrap/tests/testType.cpp b/wrap/tests/testType.cpp index f61e81c62..abf3cf65f 100644 --- a/wrap/tests/testType.cpp +++ b/wrap/tests/testType.cpp @@ -22,6 +22,22 @@ using namespace std; using namespace wrap; +//****************************************************************************** +TEST( Type, Constructor1 ) { + Qualified actual("Point2"); + EXPECT(actual.namespaces().empty()); + EXPECT(actual.name()=="Point2"); + EXPECT(actual.category==Qualified::CLASS); +} + +//****************************************************************************** +TEST( Type, Constructor2 ) { + Qualified actual("Point3",Qualified::CLASS); + EXPECT(actual.namespaces().empty()); + EXPECT(actual.name()=="Point3"); + EXPECT(actual.category==Qualified::CLASS); +} + //****************************************************************************** TEST( Type, grammar ) { From c661329ac1909156702d35f73b5ad8c9f4088be5 Mon Sep 17 00:00:00 2001 From: dellaert Date: Sun, 30 Nov 2014 23:24:24 +0100 Subject: [PATCH 057/126] ReturnType grammar --- wrap/ReturnType.h | 2 + wrap/ReturnValue.h | 2 + wrap/tests/testReturnValue.cpp | 73 ++++++++++++++++++++++++++++++++-- 3 files changed, 74 insertions(+), 3 deletions(-) diff --git a/wrap/ReturnType.h b/wrap/ReturnType.h index 64ef26991..f9d8b318a 100644 --- a/wrap/ReturnType.h +++ b/wrap/ReturnType.h @@ -22,6 +22,8 @@ struct ReturnType: public Qualified { bool isPtr; + friend struct ReturnValueGrammar; + /// Makes a void type ReturnType() : isPtr(false) { diff --git a/wrap/ReturnValue.h b/wrap/ReturnValue.h index 1ab844043..7fab5faca 100644 --- a/wrap/ReturnValue.h +++ b/wrap/ReturnValue.h @@ -25,6 +25,8 @@ struct ReturnValue { bool isPair; ReturnType type1, type2; + friend struct ReturnValueGrammar; + /// Constructor ReturnValue() : isPair(false) { diff --git a/wrap/tests/testReturnValue.cpp b/wrap/tests/testReturnValue.cpp index 3cd7e63ca..8b9774fe4 100644 --- a/wrap/tests/testReturnValue.cpp +++ b/wrap/tests/testReturnValue.cpp @@ -34,13 +34,71 @@ TEST( ReturnType, Constructor1 ) { //****************************************************************************** TEST( ReturnType, Constructor2 ) { - ReturnType actual("Point3",Qualified::CLASS, true); + ReturnType actual("Point3", Qualified::CLASS, true); EXPECT(actual.namespaces().empty()); EXPECT(actual.name()=="Point3"); EXPECT(actual.category==Qualified::CLASS); EXPECT(actual.isPtr); } +//****************************************************************************** +// http://boost-spirit.com/distrib/spirit_1_8_2/libs/spirit/doc/grammar.html +struct ReturnTypeGrammar: public classic::grammar { + + wrap::ReturnType& result_; ///< successful parse will be placed in here + + TypeGrammar type_g; + + /// Construct ReturnType grammar and specify where result is placed + ReturnTypeGrammar(wrap::ReturnType& result) : + result_(result), type_g(result_) { + } + + /// Definition of type grammar + template + struct definition { + + classic::rule type_p; + + definition(ReturnTypeGrammar const& self) { + using namespace classic; + type_p = self.type_g >> !ch_p('*')[assign_a(self.result_.isPtr, T)]; + } + + classic::rule const& start() const { + return type_p; + } + + }; +}; +// ReturnTypeGrammar + +//****************************************************************************** +TEST( ReturnType, grammar ) { + + using classic::space_p; + + // Create type grammar that will place result in actual + ReturnType actual; + ReturnTypeGrammar g(actual); + + EXPECT(parse("Point3", g, space_p).full); + EXPECT( actual==ReturnType("Point3")); + actual.clear(); + + EXPECT(parse("Test*", g, space_p).full); + EXPECT( actual==ReturnType("Test",Qualified::CLASS,true)); + actual.clear(); + + EXPECT(parse("VectorNotEigen", g, space_p).full); + EXPECT(actual==ReturnType("VectorNotEigen")); + actual.clear(); + + EXPECT(parse("double", g, space_p).full); + EXPECT(actual==ReturnType("double",Qualified::BASIS)); + actual.clear(); +} + //****************************************************************************** TEST( ReturnValue, Constructor ) { ReturnValue actual(ReturnType("Point2"), ReturnType("Point3")); @@ -55,7 +113,7 @@ struct ReturnValueGrammar: public classic::grammar { wrap::ReturnValue& result_; ///< successful parse will be placed in here - TypeGrammar returnType1_g, returnType2_g; + ReturnTypeGrammar returnType1_g, returnType2_g; /// Construct type grammar and specify where result is placed ReturnValueGrammar(wrap::ReturnValue& result) : @@ -97,7 +155,16 @@ TEST( ReturnValue, grammar ) { EXPECT(parse("pair", g, space_p).full); EXPECT( actual==ReturnValue(ReturnType("Point2"),ReturnType("Point3"))); - cout << actual << endl; + actual.clear(); + + EXPECT(parse("pair", g, space_p).full); + EXPECT( actual==ReturnValue( // + ReturnType("Test",Qualified::CLASS,true),ReturnType("Test"))); + actual.clear(); + + EXPECT(parse("pair", g, space_p).full); + EXPECT( actual==ReturnValue(ReturnType("Test"), // + ReturnType("Test",Qualified::CLASS,true))); actual.clear(); EXPECT(parse("VectorNotEigen", g, space_p).full); From e9915fe25c68da1695ad1164b963e144c7f7c8c4 Mon Sep 17 00:00:00 2001 From: dellaert Date: Sun, 30 Nov 2014 23:26:07 +0100 Subject: [PATCH 058/126] Moved to headers --- wrap/ReturnType.h | 32 ++++++++++++++++ wrap/ReturnValue.h | 37 ++++++++++++++++++ wrap/tests/testReturnValue.cpp | 69 ---------------------------------- 3 files changed, 69 insertions(+), 69 deletions(-) diff --git a/wrap/ReturnType.h b/wrap/ReturnType.h index f9d8b318a..1c67a1d9a 100644 --- a/wrap/ReturnType.h +++ b/wrap/ReturnType.h @@ -62,4 +62,36 @@ private: }; +//****************************************************************************** +// http://boost-spirit.com/distrib/spirit_1_8_2/libs/spirit/doc/grammar.html +struct ReturnTypeGrammar: public classic::grammar { + + wrap::ReturnType& result_; ///< successful parse will be placed in here + + TypeGrammar type_g; + + /// Construct ReturnType grammar and specify where result is placed + ReturnTypeGrammar(wrap::ReturnType& result) : + result_(result), type_g(result_) { + } + + /// Definition of type grammar + template + struct definition { + + classic::rule type_p; + + definition(ReturnTypeGrammar const& self) { + using namespace classic; + type_p = self.type_g >> !ch_p('*')[assign_a(self.result_.isPtr, T)]; + } + + classic::rule const& start() const { + return type_p; + } + + }; +}; +// ReturnTypeGrammar + } // \namespace wrap diff --git a/wrap/ReturnValue.h b/wrap/ReturnValue.h index 7fab5faca..b23cbf681 100644 --- a/wrap/ReturnValue.h +++ b/wrap/ReturnValue.h @@ -77,4 +77,41 @@ struct ReturnValue { }; +//****************************************************************************** +// http://boost-spirit.com/distrib/spirit_1_8_2/libs/spirit/doc/grammar.html +struct ReturnValueGrammar: public classic::grammar { + + wrap::ReturnValue& result_; ///< successful parse will be placed in here + + ReturnTypeGrammar returnType1_g, returnType2_g; + + /// Construct type grammar and specify where result is placed + ReturnValueGrammar(wrap::ReturnValue& result) : + result_(result), returnType1_g(result.type1), returnType2_g(result.type2) { + } + + /// Definition of type grammar + template + struct definition { + + classic::rule pair_p, returnValue_p; + + definition(ReturnValueGrammar const& self) { + + using namespace classic; + + pair_p = (str_p("pair") >> '<' >> self.returnType1_g >> ',' + >> self.returnType2_g >> '>')[assign_a(self.result_.isPair, T)]; + + returnValue_p = pair_p | self.returnType1_g; + } + + classic::rule const& start() const { + return returnValue_p; + } + + }; +}; +// ReturnValueGrammar + } // \namespace wrap diff --git a/wrap/tests/testReturnValue.cpp b/wrap/tests/testReturnValue.cpp index 8b9774fe4..b604bf8f8 100644 --- a/wrap/tests/testReturnValue.cpp +++ b/wrap/tests/testReturnValue.cpp @@ -41,38 +41,6 @@ TEST( ReturnType, Constructor2 ) { EXPECT(actual.isPtr); } -//****************************************************************************** -// http://boost-spirit.com/distrib/spirit_1_8_2/libs/spirit/doc/grammar.html -struct ReturnTypeGrammar: public classic::grammar { - - wrap::ReturnType& result_; ///< successful parse will be placed in here - - TypeGrammar type_g; - - /// Construct ReturnType grammar and specify where result is placed - ReturnTypeGrammar(wrap::ReturnType& result) : - result_(result), type_g(result_) { - } - - /// Definition of type grammar - template - struct definition { - - classic::rule type_p; - - definition(ReturnTypeGrammar const& self) { - using namespace classic; - type_p = self.type_g >> !ch_p('*')[assign_a(self.result_.isPtr, T)]; - } - - classic::rule const& start() const { - return type_p; - } - - }; -}; -// ReturnTypeGrammar - //****************************************************************************** TEST( ReturnType, grammar ) { @@ -107,43 +75,6 @@ TEST( ReturnValue, Constructor ) { EXPECT(actual.isPair); } -//****************************************************************************** -// http://boost-spirit.com/distrib/spirit_1_8_2/libs/spirit/doc/grammar.html -struct ReturnValueGrammar: public classic::grammar { - - wrap::ReturnValue& result_; ///< successful parse will be placed in here - - ReturnTypeGrammar returnType1_g, returnType2_g; - - /// Construct type grammar and specify where result is placed - ReturnValueGrammar(wrap::ReturnValue& result) : - result_(result), returnType1_g(result.type1), returnType2_g(result.type2) { - } - - /// Definition of type grammar - template - struct definition { - - classic::rule pair_p, returnValue_p; - - definition(ReturnValueGrammar const& self) { - - using namespace classic; - - pair_p = (str_p("pair") >> '<' >> self.returnType1_g >> ',' - >> self.returnType2_g >> '>')[assign_a(self.result_.isPair, T)]; - - returnValue_p = pair_p | self.returnType1_g; - } - - classic::rule const& start() const { - return returnValue_p; - } - - }; -}; -// ReturnValueGrammar - //****************************************************************************** TEST( ReturnValue, grammar ) { From 49870be846cc84c42af29b3292d8edc768f4b13b Mon Sep 17 00:00:00 2001 From: dellaert Date: Sun, 30 Nov 2014 23:46:25 +0100 Subject: [PATCH 059/126] Another test --- wrap/tests/testReturnValue.cpp | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/wrap/tests/testReturnValue.cpp b/wrap/tests/testReturnValue.cpp index b604bf8f8..720b120b4 100644 --- a/wrap/tests/testReturnValue.cpp +++ b/wrap/tests/testReturnValue.cpp @@ -105,6 +105,10 @@ TEST( ReturnValue, grammar ) { EXPECT(parse("double", g, space_p).full); EXPECT(actual==ReturnValue(ReturnType("double",Qualified::BASIS))); actual.clear(); + + EXPECT(parse("void", g, space_p).full); + EXPECT(actual==ReturnValue(ReturnType("void",Qualified::VOID))); + actual.clear(); } //****************************************************************************** From f6faabf5421a7059a1d1bc2832714c21eee5558b Mon Sep 17 00:00:00 2001 From: dellaert Date: Sun, 30 Nov 2014 23:47:55 +0100 Subject: [PATCH 060/126] Temporarily checked in wrong tests to be able to fix everything else --- wrap/tests/expected2/MyTemplatePoint2.m | 4 +- wrap/tests/expected2/MyTemplatePoint3.m | 4 +- wrap/tests/expected2/geometry_wrapper.cpp | 60 +++++++++++------------ 3 files changed, 32 insertions(+), 36 deletions(-) diff --git a/wrap/tests/expected2/MyTemplatePoint2.m b/wrap/tests/expected2/MyTemplatePoint2.m index ace466ed7..d7d84876b 100644 --- a/wrap/tests/expected2/MyTemplatePoint2.m +++ b/wrap/tests/expected2/MyTemplatePoint2.m @@ -83,7 +83,7 @@ classdef MyTemplatePoint2 < MyBase % RETURN_T usage: return_T(Point2 value) : returns gtsam::Point2 % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html if length(varargin) == 1 && isa(varargin{1},'gtsam.Point2') - varargout{1} = geometry_wrapper(52, this, varargin{:}); + geometry_wrapper(52, this, varargin{:}); else error('Arguments do not match any overload of function MyTemplatePoint2.return_T'); end @@ -93,7 +93,7 @@ classdef MyTemplatePoint2 < MyBase % RETURN_TPTR usage: return_Tptr(Point2 value) : returns gtsam::Point2 % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html if length(varargin) == 1 && isa(varargin{1},'gtsam.Point2') - varargout{1} = geometry_wrapper(53, this, varargin{:}); + geometry_wrapper(53, this, varargin{:}); else error('Arguments do not match any overload of function MyTemplatePoint2.return_Tptr'); end diff --git a/wrap/tests/expected2/MyTemplatePoint3.m b/wrap/tests/expected2/MyTemplatePoint3.m index bd0966ef1..190b3eca0 100644 --- a/wrap/tests/expected2/MyTemplatePoint3.m +++ b/wrap/tests/expected2/MyTemplatePoint3.m @@ -83,7 +83,7 @@ classdef MyTemplatePoint3 < MyBase % RETURN_T usage: return_T(Point3 value) : returns gtsam::Point3 % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html if length(varargin) == 1 && isa(varargin{1},'gtsam.Point3') - varargout{1} = geometry_wrapper(67, this, varargin{:}); + geometry_wrapper(67, this, varargin{:}); else error('Arguments do not match any overload of function MyTemplatePoint3.return_T'); end @@ -93,7 +93,7 @@ classdef MyTemplatePoint3 < MyBase % RETURN_TPTR usage: return_Tptr(Point3 value) : returns gtsam::Point3 % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html if length(varargin) == 1 && isa(varargin{1},'gtsam.Point3') - varargout{1} = geometry_wrapper(68, this, varargin{:}); + geometry_wrapper(68, this, varargin{:}); else error('Arguments do not match any overload of function MyTemplatePoint3.return_Tptr'); end diff --git a/wrap/tests/expected2/geometry_wrapper.cpp b/wrap/tests/expected2/geometry_wrapper.cpp index dbe60bb63..c937a2f5d 100644 --- a/wrap/tests/expected2/geometry_wrapper.cpp +++ b/wrap/tests/expected2/geometry_wrapper.cpp @@ -618,60 +618,58 @@ void MyTemplatePoint2_accept_Tptr_49(int nargout, mxArray *out[], int nargin, co void MyTemplatePoint2_create_MixedPtrs_50(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { - typedef boost::shared_ptr SharedPoint2; - typedef boost::shared_ptr SharedPoint2; typedef boost::shared_ptr Shared; checkArguments("create_MixedPtrs",nargout,nargin-1,0); Shared obj = unwrap_shared_ptr(in[0], "ptr_MyTemplatePoint2"); pair< gtsam::Point2, SharedPoint2 > pairResult = obj->create_MixedPtrs(); - out[0] = wrap_shared_ptr(SharedPoint2(new gtsam::Point2(pairResult.first)),"gtsam.Point2", false); - out[1] = wrap_shared_ptr(pairResult.second,"gtsam.Point2", false); + out[0] = wrap< gtsam::Point2 >(pairResult.first); + SharedPoint2* ret = new SharedPoint2(pairResult.second); + out[1] = wrap_shared_ptr(ret,"gtsam.Point2"); } void MyTemplatePoint2_create_ptrs_51(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { - typedef boost::shared_ptr SharedPoint2; - typedef boost::shared_ptr SharedPoint2; typedef boost::shared_ptr Shared; checkArguments("create_ptrs",nargout,nargin-1,0); Shared obj = unwrap_shared_ptr(in[0], "ptr_MyTemplatePoint2"); pair< SharedPoint2, SharedPoint2 > pairResult = obj->create_ptrs(); - out[0] = wrap_shared_ptr(pairResult.first,"gtsam.Point2", false); - out[1] = wrap_shared_ptr(pairResult.second,"gtsam.Point2", false); + SharedPoint2* ret = new SharedPoint2(pairResult.first); + out[0] = wrap_shared_ptr(ret,"gtsam.Point2"); + SharedPoint2* ret = new SharedPoint2(pairResult.second); + out[1] = wrap_shared_ptr(ret,"gtsam.Point2"); } void MyTemplatePoint2_return_T_52(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { - typedef boost::shared_ptr SharedPoint2; typedef boost::shared_ptr Shared; checkArguments("return_T",nargout,nargin-1,1); Shared obj = unwrap_shared_ptr(in[0], "ptr_MyTemplatePoint2"); boost::shared_ptr value = unwrap_shared_ptr< gtsam::Point2 >(in[1], "ptr_gtsamPoint2"); - out[0] = wrap_shared_ptr(SharedPoint2(new gtsam::Point2(obj->return_T(value))),"gtsam.Point2", false); + out[0] = wrap< gtsam::Point2 >(obj->return_T(value)); } void MyTemplatePoint2_return_Tptr_53(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { - typedef boost::shared_ptr SharedPoint2; typedef boost::shared_ptr Shared; checkArguments("return_Tptr",nargout,nargin-1,1); Shared obj = unwrap_shared_ptr(in[0], "ptr_MyTemplatePoint2"); boost::shared_ptr value = unwrap_shared_ptr< gtsam::Point2 >(in[1], "ptr_gtsamPoint2"); - out[0] = wrap_shared_ptr(obj->return_Tptr(value),"gtsam.Point2", false); + SharedPoint2* ret = new SharedPoint2(obj->return_Tptr(value)); + out[0] = wrap_shared_ptr(ret,"gtsam.Point2"); } void MyTemplatePoint2_return_ptrs_54(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { - typedef boost::shared_ptr SharedPoint2; - typedef boost::shared_ptr SharedPoint2; typedef boost::shared_ptr Shared; checkArguments("return_ptrs",nargout,nargin-1,2); Shared obj = unwrap_shared_ptr(in[0], "ptr_MyTemplatePoint2"); boost::shared_ptr p1 = unwrap_shared_ptr< gtsam::Point2 >(in[1], "ptr_gtsamPoint2"); boost::shared_ptr p2 = unwrap_shared_ptr< gtsam::Point2 >(in[2], "ptr_gtsamPoint2"); pair< SharedPoint2, SharedPoint2 > pairResult = obj->return_ptrs(p1,p2); - out[0] = wrap_shared_ptr(pairResult.first,"gtsam.Point2", false); - out[1] = wrap_shared_ptr(pairResult.second,"gtsam.Point2", false); + SharedPoint2* ret = new SharedPoint2(pairResult.first); + out[0] = wrap_shared_ptr(ret,"gtsam.Point2"); + SharedPoint2* ret = new SharedPoint2(pairResult.second); + out[1] = wrap_shared_ptr(ret,"gtsam.Point2"); } void MyTemplatePoint2_templatedMethod_55(int nargout, mxArray *out[], int nargin, const mxArray *in[]) @@ -780,60 +778,58 @@ void MyTemplatePoint3_accept_Tptr_64(int nargout, mxArray *out[], int nargin, co void MyTemplatePoint3_create_MixedPtrs_65(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { - typedef boost::shared_ptr SharedPoint3; - typedef boost::shared_ptr SharedPoint3; typedef boost::shared_ptr Shared; checkArguments("create_MixedPtrs",nargout,nargin-1,0); Shared obj = unwrap_shared_ptr(in[0], "ptr_MyTemplatePoint3"); pair< gtsam::Point3, SharedPoint3 > pairResult = obj->create_MixedPtrs(); - out[0] = wrap_shared_ptr(SharedPoint3(new gtsam::Point3(pairResult.first)),"gtsam.Point3", false); - out[1] = wrap_shared_ptr(pairResult.second,"gtsam.Point3", false); + out[0] = wrap< gtsam::Point3 >(pairResult.first); + SharedPoint3* ret = new SharedPoint3(pairResult.second); + out[1] = wrap_shared_ptr(ret,"gtsam.Point3"); } void MyTemplatePoint3_create_ptrs_66(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { - typedef boost::shared_ptr SharedPoint3; - typedef boost::shared_ptr SharedPoint3; typedef boost::shared_ptr Shared; checkArguments("create_ptrs",nargout,nargin-1,0); Shared obj = unwrap_shared_ptr(in[0], "ptr_MyTemplatePoint3"); pair< SharedPoint3, SharedPoint3 > pairResult = obj->create_ptrs(); - out[0] = wrap_shared_ptr(pairResult.first,"gtsam.Point3", false); - out[1] = wrap_shared_ptr(pairResult.second,"gtsam.Point3", false); + SharedPoint3* ret = new SharedPoint3(pairResult.first); + out[0] = wrap_shared_ptr(ret,"gtsam.Point3"); + SharedPoint3* ret = new SharedPoint3(pairResult.second); + out[1] = wrap_shared_ptr(ret,"gtsam.Point3"); } void MyTemplatePoint3_return_T_67(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { - typedef boost::shared_ptr SharedPoint3; typedef boost::shared_ptr Shared; checkArguments("return_T",nargout,nargin-1,1); Shared obj = unwrap_shared_ptr(in[0], "ptr_MyTemplatePoint3"); boost::shared_ptr value = unwrap_shared_ptr< gtsam::Point3 >(in[1], "ptr_gtsamPoint3"); - out[0] = wrap_shared_ptr(SharedPoint3(new gtsam::Point3(obj->return_T(value))),"gtsam.Point3", false); + out[0] = wrap< gtsam::Point3 >(obj->return_T(value)); } void MyTemplatePoint3_return_Tptr_68(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { - typedef boost::shared_ptr SharedPoint3; typedef boost::shared_ptr Shared; checkArguments("return_Tptr",nargout,nargin-1,1); Shared obj = unwrap_shared_ptr(in[0], "ptr_MyTemplatePoint3"); boost::shared_ptr value = unwrap_shared_ptr< gtsam::Point3 >(in[1], "ptr_gtsamPoint3"); - out[0] = wrap_shared_ptr(obj->return_Tptr(value),"gtsam.Point3", false); + SharedPoint3* ret = new SharedPoint3(obj->return_Tptr(value)); + out[0] = wrap_shared_ptr(ret,"gtsam.Point3"); } void MyTemplatePoint3_return_ptrs_69(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { - typedef boost::shared_ptr SharedPoint3; - typedef boost::shared_ptr SharedPoint3; typedef boost::shared_ptr Shared; checkArguments("return_ptrs",nargout,nargin-1,2); Shared obj = unwrap_shared_ptr(in[0], "ptr_MyTemplatePoint3"); boost::shared_ptr p1 = unwrap_shared_ptr< gtsam::Point3 >(in[1], "ptr_gtsamPoint3"); boost::shared_ptr p2 = unwrap_shared_ptr< gtsam::Point3 >(in[2], "ptr_gtsamPoint3"); pair< SharedPoint3, SharedPoint3 > pairResult = obj->return_ptrs(p1,p2); - out[0] = wrap_shared_ptr(pairResult.first,"gtsam.Point3", false); - out[1] = wrap_shared_ptr(pairResult.second,"gtsam.Point3", false); + SharedPoint3* ret = new SharedPoint3(pairResult.first); + out[0] = wrap_shared_ptr(ret,"gtsam.Point3"); + SharedPoint3* ret = new SharedPoint3(pairResult.second); + out[1] = wrap_shared_ptr(ret,"gtsam.Point3"); } void MyTemplatePoint3_templatedMethod_70(int nargout, mxArray *out[], int nargin, const mxArray *in[]) From 47a44ee7dbed8c214264873fc0f6a5f3a8c0398b Mon Sep 17 00:00:00 2001 From: dellaert Date: Mon, 1 Dec 2014 00:01:31 +0100 Subject: [PATCH 061/126] typo --- wrap/Qualified.h | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/wrap/Qualified.h b/wrap/Qualified.h index 7f707319d..391cfa1fc 100644 --- a/wrap/Qualified.h +++ b/wrap/Qualified.h @@ -143,7 +143,7 @@ struct basic_rules { typedef classic::rule Rule; Rule comments_p, basisType_p, eigenType_p, keywords_p, stlType_p, name_p, - className_p, namepsace_p; + className_p, namespace_p; basic_rules() { @@ -166,7 +166,7 @@ struct basic_rules { className_p = (lexeme_d[upper_p >> *(alnum_p | '_')] - eigenType_p - keywords_p) | stlType_p; - namepsace_p = lexeme_d[lower_p >> *(alnum_p | '_')] - keywords_p; + namespace_p = lexeme_d[lower_p >> *(alnum_p | '_')] - keywords_p; } }; @@ -213,7 +213,7 @@ public: [assign_a(self.result_.name_)] // [assign_a(self.result_.category, EIGEN)]; - namespace_del_p = basic_rules::namepsace_p // + namespace_del_p = basic_rules::namespace_p // [push_back_a(self.result_.namespaces_)] >> str_p("::"); class_p = *namespace_del_p >> basic_rules::className_p // From 674344ea0e6f12cd883323610df961d3c3e03d8e Mon Sep 17 00:00:00 2001 From: dellaert Date: Mon, 1 Dec 2014 00:33:54 +0100 Subject: [PATCH 062/126] Pushed through use of some grammars --- wrap/Module.cpp | 77 +++++++++++++++++++++++++------------------------ 1 file changed, 39 insertions(+), 38 deletions(-) diff --git a/wrap/Module.cpp b/wrap/Module.cpp index 21c5262da..fac1f4f02 100644 --- a/wrap/Module.cpp +++ b/wrap/Module.cpp @@ -118,9 +118,11 @@ void Module::parseMarkup(const std::string& data) { // parse "gtsam::Pose2" and add to templateArgValues Qualified templateArgValue; vector templateArgValues; - Rule templateArgValue_p = - TypeGrammar(templateArgValue) - [push_back_a( templateArgValues, templateArgValue)]; + TypeGrammar templateArgValue_g(templateArgValue); + Rule templateArgValue_p = templateArgValue_g + [assign_a(templateArgValue.category, Qualified::VOID)] // TODO: why ? + [push_back_a(templateArgValues, templateArgValue)] + [clear_a(templateArgValue)]; // template string templateArgName; @@ -132,17 +134,20 @@ void Module::parseMarkup(const std::string& data) { // parse "gtsam::Pose2" and add to singleInstantiation.typeList TemplateInstantiationTypedef singleInstantiation, singleInstantiation0; - Rule templateSingleInstantiationArg_p = - TypeGrammar(templateArgValue) - [push_back_a(singleInstantiation.typeList, templateArgValue)]; + Rule templateSingleInstantiationArg_p = templateArgValue_g + [push_back_a(singleInstantiation.typeList, templateArgValue)] + [clear_a(templateArgValue)]; // typedef gtsam::RangeFactor RangeFactorPosePoint2; + vector namespaces; // current namespace tag + TypeGrammar instantiationClass_g(singleInstantiation.class_); Rule templateSingleInstantiation_p = - (str_p("typedef") >> - TypeGrammar(singleInstantiation.class_) >> - '<' >> templateSingleInstantiationArg_p >> *(',' >> templateSingleInstantiationArg_p) >> '>' >> - TypeGrammar(singleInstantiation) >> + (str_p("typedef") >> instantiationClass_g >> + '<' >> templateSingleInstantiationArg_p >> *(',' >> templateSingleInstantiationArg_p) >> + '>' >> + basic.className_p[assign_a(singleInstantiation.name_)] >> ';') + [assign_a(singleInstantiation.namespaces_, namespaces)] [push_back_a(templateInstantiationTypedefs, singleInstantiation)] [assign_a(singleInstantiation, singleInstantiation0)]; @@ -152,30 +157,27 @@ void Module::parseMarkup(const std::string& data) { '<' >> basic.name_p[push_back_a(cls.templateArgs)] >> *(',' >> basic.name_p[push_back_a(cls.templateArgs)]) >> '>'); - // Argument list + // NOTE: allows for pointers to all types ArgumentList args; - ArgumentListGrammar argumentlist_g(args); + Argument arg,arg0; + ArgumentGrammar argument_g(arg); + Rule argument_p = argument_g[push_back_a(args, arg)][assign_a(arg, arg0)]; + + Rule argumentList_p = !argument_p >> * (',' >> argument_p); // parse class constructor Constructor constructor0(verbose), constructor(verbose); Rule constructor_p = - (basic.className_p >> '(' >> argumentlist_g >> ')' >> ';' >> !basic.comments_p) + (basic.className_p >> '(' >> argumentList_p >> ')' >> ';' >> !basic.comments_p) [bl::bind(&Constructor::push_back, bl::var(constructor), bl::var(args))] [clear_a(args)]; - ReturnType retType0, retType; - Rule returnType_p = TypeGrammar(retType); - + vector namespaces_return; /// namespace for current return type + Rule namespace_ret_p = basic.namespace_p[push_back_a(namespaces_return)] >> str_p("::"); + ReturnValue retVal0, retVal; - Rule returnType1_p = returnType_p[assign_a(retVal.type1,retType)][assign_a(retType,retType0)]; - Rule returnType2_p = returnType_p[assign_a(retVal.type2,retType)][assign_a(retType,retType0)]; + ReturnValueGrammar returnValue_g(retVal); - Rule pair_p = - (str_p("pair") >> '<' >> returnType1_p >> ',' >> returnType2_p >> '>') - [assign_a(retVal.isPair,true)]; - - Rule returnValue_p = pair_p | returnType1_p; - Rule methodName_p = lexeme_d[(upper_p | lower_p) >> *(alnum_p | '_')]; // gtsam::Values retract(const gtsam::VectorValues& delta) const; @@ -183,8 +185,8 @@ void Module::parseMarkup(const std::string& data) { bool isConst, isConst0 = false; Rule method_p = !templateArgValues_p >> - (returnValue_p >> methodName_p[assign_a(methodName)] >> - '(' >> argumentlist_g >> ')' >> + (returnValue_g >> methodName_p[assign_a(methodName)] >> + '(' >> argumentList_p >> ')' >> !str_p("const")[assign_a(isConst,true)] >> ';' >> *basic.comments_p) [bl::bind(&Class::addMethod, bl::var(cls), verbose, bl::var(isConst), bl::var(methodName), bl::var(args), bl::var(retVal), @@ -197,8 +199,8 @@ void Module::parseMarkup(const std::string& data) { Rule staticMethodName_p = lexeme_d[(upper_p | lower_p) >> *(alnum_p | '_')]; Rule static_method_p = - (str_p("static") >> returnValue_p >> staticMethodName_p[assign_a(methodName)] >> - '(' >> argumentlist_g >> ')' >> ';' >> *basic.comments_p) + (str_p("static") >> returnValue_g >> staticMethodName_p[assign_a(methodName)] >> + '(' >> argumentList_p >> ')' >> ';' >> *basic.comments_p) [bl::bind(&StaticMethod::addOverload, bl::var(cls.static_methods)[bl::var(methodName)], bl::var(methodName), bl::var(args), bl::var(retVal), Qualified(),verbose)] @@ -208,7 +210,6 @@ void Module::parseMarkup(const std::string& data) { Rule functions_p = constructor_p | method_p | static_method_p; // parse a full class - vector namespaces; // current namespace tag vector templateInstantiations; Rule class_p = eps_p[assign_a(cls,cls0)] @@ -237,8 +238,8 @@ void Module::parseMarkup(const std::string& data) { // parse a global function Qualified globalFunction; Rule global_function_p = - (returnValue_p >> staticMethodName_p[assign_a(globalFunction.name_)] >> - '(' >> argumentlist_g >> ')' >> ';' >> *basic.comments_p) + (returnValue_g >> staticMethodName_p[assign_a(globalFunction.name_)] >> + '(' >> argumentList_p >> ')' >> ';' >> *basic.comments_p) [assign_a(globalFunction.namespaces_,namespaces)] [bl::bind(&GlobalFunction::addOverload, bl::var(global_functions)[bl::var(globalFunction.name_)], @@ -256,7 +257,7 @@ void Module::parseMarkup(const std::string& data) { Rule namespace_def_p = (str_p("namespace") - >> basic.namepsace_p[push_back_a(namespaces)] + >> basic.namespace_p[push_back_a(namespaces)] >> ch_p('{') >> *(include_p | class_p | templateSingleInstantiation_p | global_function_p | namespace_def_p | basic.comments_p) >> ch_p('}')) @@ -271,7 +272,7 @@ void Module::parseMarkup(const std::string& data) { Rule forward_declaration_p = !(str_p("virtual")[assign_a(fwDec.isVirtual, true)]) >> str_p("class") - >> (*(basic.namepsace_p >> str_p("::")) >> basic.className_p)[assign_a(fwDec.name)] + >> (*(basic.namespace_p >> str_p("::")) >> basic.className_p)[assign_a(fwDec.name)] >> ch_p(';') [push_back_a(forward_declarations, fwDec)] [assign_a(fwDec, fwDec0)]; @@ -284,7 +285,6 @@ void Module::parseMarkup(const std::string& data) { //---------------------------------------------------------------------------- // for debugging, define BOOST_SPIRIT_DEBUG -#define BOOST_SPIRIT_DEBUG # ifdef BOOST_SPIRIT_DEBUG BOOST_SPIRIT_DEBUG_NODE(className_p); BOOST_SPIRIT_DEBUG_NODE(classPtr_p); @@ -298,7 +298,7 @@ void Module::parseMarkup(const std::string& data) { BOOST_SPIRIT_DEBUG_NODE(returnType2_p); BOOST_SPIRIT_DEBUG_NODE(pair_p); BOOST_SPIRIT_DEBUG_NODE(void_p); - BOOST_SPIRIT_DEBUG_NODE(returnValue_p); + BOOST_SPIRIT_DEBUG_NODE(returnValue_g); BOOST_SPIRIT_DEBUG_NODE(methodName_p); BOOST_SPIRIT_DEBUG_NODE(method_p); BOOST_SPIRIT_DEBUG_NODE(class_p); @@ -312,8 +312,9 @@ void Module::parseMarkup(const std::string& data) { if(!info.full) { printf("parsing stopped at \n%.20s\n",info.stop); cout << "Stopped near:\n" - "class '" << cls.name() << "'\n" - "method '" << methodName << endl; + "class '" << cls.name_ << "'\n" + "method '" << methodName << "'\n" + "argument '" << arg.name << "'" << endl; throw ParseFailed((int)info.length); } @@ -481,7 +482,7 @@ vector Module::ExpandTypedefInstantiations(const vector& classes, vector Module::GenerateValidTypes(const vector& classes, const vector forwardDeclarations) { vector validTypes; BOOST_FOREACH(const ForwardDeclaration& fwDec, forwardDeclarations) { - validTypes.push_back(fwDec.name); + validTypes.push_back(fwDec.name); } validTypes.push_back("void"); validTypes.push_back("string"); From e9f4b1d65a91cddc914726c9132456e479128d8e Mon Sep 17 00:00:00 2001 From: Andrew Melim Date: Mon, 1 Dec 2014 02:12:08 -0500 Subject: [PATCH 063/126] Remove header from MetisIndex, replace idx_t with int32_t --- gtsam/inference/MetisIndex-inl.h | 12 ++++++------ gtsam/inference/MetisIndex.h | 17 ++++++++--------- 2 files changed, 14 insertions(+), 15 deletions(-) diff --git a/gtsam/inference/MetisIndex-inl.h b/gtsam/inference/MetisIndex-inl.h index 50bed2e3b..7299d7c8a 100644 --- a/gtsam/inference/MetisIndex-inl.h +++ b/gtsam/inference/MetisIndex-inl.h @@ -26,8 +26,8 @@ namespace gtsam { /* ************************************************************************* */ template void MetisIndex::augment(const FactorGraph& factors) { - std::map > iAdjMap; // Stores a set of keys that are adjacent to key x, with adjMap.first - std::map >::iterator iAdjMapIt; + std::map > iAdjMap; // Stores a set of keys that are adjacent to key x, with adjMap.first + std::map >::iterator iAdjMapIt; std::set keySet; /* ********** Convert to CSR format ********** */ @@ -36,7 +36,7 @@ void MetisIndex::augment(const FactorGraph& factors) { // starting at index xadj[i] and ending at(but not including) // index xadj[i + 1](i.e., adjncy[xadj[i]] through // and including adjncy[xadj[i + 1] - 1]). - idx_t keyCounter = 0; + int32_t keyCounter = 0; // First: Record a copy of each key inside the factorgraph and create a // key to integer mapping. This is referenced during the adjaceny step @@ -58,7 +58,7 @@ void MetisIndex::augment(const FactorGraph& factors) { BOOST_FOREACH(const Key& k1, *factors[i]) BOOST_FOREACH(const Key& k2, *factors[i]) if (k1 != k2) { - // Store both in Key and idx_t format + // Store both in Key and int32_t format int i = intKeyBMap_.left.at(k1); int j = intKeyBMap_.left.at(k2); iAdjMap[i].insert(iAdjMap[i].end(), j); @@ -71,14 +71,14 @@ void MetisIndex::augment(const FactorGraph& factors) { xadj_.push_back(0); // Always set the first index to zero for (iAdjMapIt = iAdjMap.begin(); iAdjMapIt != iAdjMap.end(); ++iAdjMapIt) { - std::vector temp; + std::vector temp; // Copy from the FastSet into a temporary vector std::copy(iAdjMapIt->second.begin(), iAdjMapIt->second.end(), std::back_inserter(temp)); // Insert each index's set in order by appending them to the end of adj_ adj_.insert(adj_.end(), temp.begin(), temp.end()); //adj_.push_back(temp); - xadj_.push_back((idx_t) adj_.size()); + xadj_.push_back((int32_t) adj_.size()); } } diff --git a/gtsam/inference/MetisIndex.h b/gtsam/inference/MetisIndex.h index 51624e29e..22b03ee5d 100644 --- a/gtsam/inference/MetisIndex.h +++ b/gtsam/inference/MetisIndex.h @@ -22,7 +22,6 @@ #include #include #include -#include // Boost bimap generates many ugly warnings in CLANG #ifdef __clang__ @@ -47,13 +46,13 @@ namespace gtsam { class GTSAM_EXPORT MetisIndex { public: typedef boost::shared_ptr shared_ptr; - typedef boost::bimap bm_type; + typedef boost::bimap bm_type; private: - FastVector xadj_; // Index of node's adjacency list in adj - FastVector adj_; // Stores ajacency lists of all nodes, appended into a single vector - FastVector iadj_; // Integer keys for passing into metis. One to one mapping with adj_; - boost::bimap intKeyBMap_; // Stores Key <-> integer value relationship + FastVector xadj_; // Index of node's adjacency list in adj + FastVector adj_; // Stores ajacency lists of all nodes, appended into a single vector + FastVector iadj_; // Integer keys for passing into metis. One to one mapping with adj_; + boost::bimap intKeyBMap_; // Stores Key <-> integer value relationship size_t nKeys_; public: @@ -84,16 +83,16 @@ public: template void augment(const FactorGraph& factors); - std::vector xadj() const { + std::vector xadj() const { return xadj_; } - std::vector adj() const { + std::vector adj() const { return adj_; } size_t nValues() const { return nKeys_; } - Key intToKey(idx_t value) const { + Key intToKey(int32_t value) const { assert(value >= 0); return intKeyBMap_.right.find(value)->second; } From 7362b4e393201888fd26454b7a808c18ed1d0c5c Mon Sep 17 00:00:00 2001 From: dellaert Date: Mon, 1 Dec 2014 10:20:54 +0100 Subject: [PATCH 064/126] Returned correct test --- wrap/tests/expected2/geometry_wrapper.cpp | 60 ++++++++++++----------- 1 file changed, 32 insertions(+), 28 deletions(-) diff --git a/wrap/tests/expected2/geometry_wrapper.cpp b/wrap/tests/expected2/geometry_wrapper.cpp index 2714f3584..9e6450d70 100644 --- a/wrap/tests/expected2/geometry_wrapper.cpp +++ b/wrap/tests/expected2/geometry_wrapper.cpp @@ -618,58 +618,60 @@ void MyTemplatePoint2_accept_Tptr_49(int nargout, mxArray *out[], int nargin, co void MyTemplatePoint2_create_MixedPtrs_50(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { + typedef boost::shared_ptr SharedPoint2; + typedef boost::shared_ptr SharedPoint2; typedef boost::shared_ptr Shared; checkArguments("create_MixedPtrs",nargout,nargin-1,0); Shared obj = unwrap_shared_ptr(in[0], "ptr_MyTemplatePoint2"); pair< gtsam::Point2, SharedPoint2 > pairResult = obj->create_MixedPtrs(); - out[0] = wrap< gtsam::Point2 >(pairResult.first); - SharedPoint2* ret = new SharedPoint2(pairResult.second); - out[1] = wrap_shared_ptr(ret,"gtsam.Point2"); + out[0] = wrap_shared_ptr(SharedPoint2(new gtsam::Point2(pairResult.first)),"gtsam.Point2", false); + out[1] = wrap_shared_ptr(pairResult.second,"gtsam.Point2", false); } void MyTemplatePoint2_create_ptrs_51(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { + typedef boost::shared_ptr SharedPoint2; + typedef boost::shared_ptr SharedPoint2; typedef boost::shared_ptr Shared; checkArguments("create_ptrs",nargout,nargin-1,0); Shared obj = unwrap_shared_ptr(in[0], "ptr_MyTemplatePoint2"); pair< SharedPoint2, SharedPoint2 > pairResult = obj->create_ptrs(); - SharedPoint2* ret = new SharedPoint2(pairResult.first); - out[0] = wrap_shared_ptr(ret,"gtsam.Point2"); - SharedPoint2* ret = new SharedPoint2(pairResult.second); - out[1] = wrap_shared_ptr(ret,"gtsam.Point2"); + out[0] = wrap_shared_ptr(pairResult.first,"gtsam.Point2", false); + out[1] = wrap_shared_ptr(pairResult.second,"gtsam.Point2", false); } void MyTemplatePoint2_return_T_52(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { + typedef boost::shared_ptr SharedPoint2; typedef boost::shared_ptr Shared; checkArguments("return_T",nargout,nargin-1,1); Shared obj = unwrap_shared_ptr(in[0], "ptr_MyTemplatePoint2"); boost::shared_ptr value = unwrap_shared_ptr< gtsam::Point2 >(in[1], "ptr_gtsamPoint2"); - out[0] = wrap< gtsam::Point2 >(obj->return_T(value)); + out[0] = wrap_shared_ptr(SharedPoint2(new gtsam::Point2(obj->return_T(value))),"gtsam.Point2", false); } void MyTemplatePoint2_return_Tptr_53(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { + typedef boost::shared_ptr SharedPoint2; typedef boost::shared_ptr Shared; checkArguments("return_Tptr",nargout,nargin-1,1); Shared obj = unwrap_shared_ptr(in[0], "ptr_MyTemplatePoint2"); boost::shared_ptr value = unwrap_shared_ptr< gtsam::Point2 >(in[1], "ptr_gtsamPoint2"); - SharedPoint2* ret = new SharedPoint2(obj->return_Tptr(value)); - out[0] = wrap_shared_ptr(ret,"gtsam.Point2"); + out[0] = wrap_shared_ptr(obj->return_Tptr(value),"gtsam.Point2", false); } void MyTemplatePoint2_return_ptrs_54(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { + typedef boost::shared_ptr SharedPoint2; + typedef boost::shared_ptr SharedPoint2; typedef boost::shared_ptr Shared; checkArguments("return_ptrs",nargout,nargin-1,2); Shared obj = unwrap_shared_ptr(in[0], "ptr_MyTemplatePoint2"); boost::shared_ptr p1 = unwrap_shared_ptr< gtsam::Point2 >(in[1], "ptr_gtsamPoint2"); boost::shared_ptr p2 = unwrap_shared_ptr< gtsam::Point2 >(in[2], "ptr_gtsamPoint2"); pair< SharedPoint2, SharedPoint2 > pairResult = obj->return_ptrs(p1,p2); - SharedPoint2* ret = new SharedPoint2(pairResult.first); - out[0] = wrap_shared_ptr(ret,"gtsam.Point2"); - SharedPoint2* ret = new SharedPoint2(pairResult.second); - out[1] = wrap_shared_ptr(ret,"gtsam.Point2"); + out[0] = wrap_shared_ptr(pairResult.first,"gtsam.Point2", false); + out[1] = wrap_shared_ptr(pairResult.second,"gtsam.Point2", false); } void MyTemplatePoint2_templatedMethod_55(int nargout, mxArray *out[], int nargin, const mxArray *in[]) @@ -778,58 +780,60 @@ void MyTemplatePoint3_accept_Tptr_64(int nargout, mxArray *out[], int nargin, co void MyTemplatePoint3_create_MixedPtrs_65(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { + typedef boost::shared_ptr SharedPoint3; + typedef boost::shared_ptr SharedPoint3; typedef boost::shared_ptr Shared; checkArguments("create_MixedPtrs",nargout,nargin-1,0); Shared obj = unwrap_shared_ptr(in[0], "ptr_MyTemplatePoint3"); pair< gtsam::Point3, SharedPoint3 > pairResult = obj->create_MixedPtrs(); - out[0] = wrap< gtsam::Point3 >(pairResult.first); - SharedPoint3* ret = new SharedPoint3(pairResult.second); - out[1] = wrap_shared_ptr(ret,"gtsam.Point3"); + out[0] = wrap_shared_ptr(SharedPoint3(new gtsam::Point3(pairResult.first)),"gtsam.Point3", false); + out[1] = wrap_shared_ptr(pairResult.second,"gtsam.Point3", false); } void MyTemplatePoint3_create_ptrs_66(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { + typedef boost::shared_ptr SharedPoint3; + typedef boost::shared_ptr SharedPoint3; typedef boost::shared_ptr Shared; checkArguments("create_ptrs",nargout,nargin-1,0); Shared obj = unwrap_shared_ptr(in[0], "ptr_MyTemplatePoint3"); pair< SharedPoint3, SharedPoint3 > pairResult = obj->create_ptrs(); - SharedPoint3* ret = new SharedPoint3(pairResult.first); - out[0] = wrap_shared_ptr(ret,"gtsam.Point3"); - SharedPoint3* ret = new SharedPoint3(pairResult.second); - out[1] = wrap_shared_ptr(ret,"gtsam.Point3"); + out[0] = wrap_shared_ptr(pairResult.first,"gtsam.Point3", false); + out[1] = wrap_shared_ptr(pairResult.second,"gtsam.Point3", false); } void MyTemplatePoint3_return_T_67(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { + typedef boost::shared_ptr SharedPoint3; typedef boost::shared_ptr Shared; checkArguments("return_T",nargout,nargin-1,1); Shared obj = unwrap_shared_ptr(in[0], "ptr_MyTemplatePoint3"); boost::shared_ptr value = unwrap_shared_ptr< gtsam::Point3 >(in[1], "ptr_gtsamPoint3"); - out[0] = wrap< gtsam::Point3 >(obj->return_T(value)); + out[0] = wrap_shared_ptr(SharedPoint3(new gtsam::Point3(obj->return_T(value))),"gtsam.Point3", false); } void MyTemplatePoint3_return_Tptr_68(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { + typedef boost::shared_ptr SharedPoint3; typedef boost::shared_ptr Shared; checkArguments("return_Tptr",nargout,nargin-1,1); Shared obj = unwrap_shared_ptr(in[0], "ptr_MyTemplatePoint3"); boost::shared_ptr value = unwrap_shared_ptr< gtsam::Point3 >(in[1], "ptr_gtsamPoint3"); - SharedPoint3* ret = new SharedPoint3(obj->return_Tptr(value)); - out[0] = wrap_shared_ptr(ret,"gtsam.Point3"); + out[0] = wrap_shared_ptr(obj->return_Tptr(value),"gtsam.Point3", false); } void MyTemplatePoint3_return_ptrs_69(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { + typedef boost::shared_ptr SharedPoint3; + typedef boost::shared_ptr SharedPoint3; typedef boost::shared_ptr Shared; checkArguments("return_ptrs",nargout,nargin-1,2); Shared obj = unwrap_shared_ptr(in[0], "ptr_MyTemplatePoint3"); boost::shared_ptr p1 = unwrap_shared_ptr< gtsam::Point3 >(in[1], "ptr_gtsamPoint3"); boost::shared_ptr p2 = unwrap_shared_ptr< gtsam::Point3 >(in[2], "ptr_gtsamPoint3"); pair< SharedPoint3, SharedPoint3 > pairResult = obj->return_ptrs(p1,p2); - SharedPoint3* ret = new SharedPoint3(pairResult.first); - out[0] = wrap_shared_ptr(ret,"gtsam.Point3"); - SharedPoint3* ret = new SharedPoint3(pairResult.second); - out[1] = wrap_shared_ptr(ret,"gtsam.Point3"); + out[0] = wrap_shared_ptr(pairResult.first,"gtsam.Point3", false); + out[1] = wrap_shared_ptr(pairResult.second,"gtsam.Point3", false); } void MyTemplatePoint3_templatedMethod_70(int nargout, mxArray *out[], int nargin, const mxArray *in[]) From 9bebedc6842642c53a0884356fe33826c5ee0751 Mon Sep 17 00:00:00 2001 From: dellaert Date: Mon, 1 Dec 2014 10:21:23 +0100 Subject: [PATCH 065/126] Better Documentation --- wrap/ReturnType.cpp | 33 +++++++++++++++++++++------------ 1 file changed, 21 insertions(+), 12 deletions(-) diff --git a/wrap/ReturnType.cpp b/wrap/ReturnType.cpp index f41a45e56..9c046ba46 100644 --- a/wrap/ReturnType.cpp +++ b/wrap/ReturnType.cpp @@ -24,30 +24,39 @@ void ReturnType::wrap_result(const string& out, const string& result, string cppType = qualifiedName("::"), matlabType = qualifiedName("."); if (category == CLASS) { + + // Handle Classes string objCopy, ptrType; - ptrType = "Shared" + name(); const bool isVirtual = typeAttributes.attributes(cppType).isVirtual; - if (isVirtual) { - if (isPtr) - objCopy = result; - else + if (isPtr) + objCopy = result; // a shared pointer can always be passed as is + else { + // but if we want an actual new object, things get more complex + if (isVirtual) + // A virtual class needs to be cloned, so the whole hierarchy is returned objCopy = result + ".clone()"; - } else { - if (isPtr) - objCopy = result; else - objCopy = ptrType + "(new " + cppType + "(" + result + "))"; + // ...but a non-virtual class can just be copied + objCopy = "Shared" + name() + "(new " + cppType + "(" + result + "))"; } + // e.g. out[1] = wrap_shared_ptr(pairResult.second,"gtsam.Point3", false); wrapperFile.oss << out << " = wrap_shared_ptr(" << objCopy << ",\"" << matlabType << "\", " << (isVirtual ? "true" : "false") << ");\n"; + } else if (isPtr) { - wrapperFile.oss << " Shared" << name() << "* ret = new Shared" << name() << "(" - << result << ");" << endl; + + // Handle shared pointer case for BASIS/EIGEN/VOID + wrapperFile.oss << "{\n Shared" << name() << "* ret = new Shared" << name() + << "(" << result << ");" << endl; wrapperFile.oss << out << " = wrap_shared_ptr(ret,\"" << matlabType - << "\");\n"; + << "\");\n}\n"; + } else if (matlabType != "void") + + // Handle normal case case for BASIS/EIGEN wrapperFile.oss << out << " = wrap< " << str(false) << " >(" << result << ");\n"; + } /* ************************************************************************* */ From 0e5332ed3ede7fbdf6dedde4e374c4495a1ff2be Mon Sep 17 00:00:00 2001 From: dellaert Date: Mon, 1 Dec 2014 10:30:47 +0100 Subject: [PATCH 066/126] Removed incorrect void, which fixed old problems and even improves on generated code. --- wrap/Module.cpp | 1 - wrap/tests/expected2/MyTemplatePoint2.m | 12 ++++++------ wrap/tests/expected2/MyTemplatePoint3.m | 12 ++++++------ wrap/tests/expected2/geometry_wrapper.cpp | 12 ++++++++---- 4 files changed, 20 insertions(+), 17 deletions(-) diff --git a/wrap/Module.cpp b/wrap/Module.cpp index 25a5a5cac..35a40c02d 100644 --- a/wrap/Module.cpp +++ b/wrap/Module.cpp @@ -119,7 +119,6 @@ void Module::parseMarkup(const std::string& data) { vector templateArgValues; TypeGrammar templateArgValue_g(templateArgValue); Rule templateArgValue_p = templateArgValue_g - [assign_a(templateArgValue.category, Qualified::VOID)] // TODO: why ? [push_back_a(templateArgValues, templateArgValue)] [clear_a(templateArgValue)]; diff --git a/wrap/tests/expected2/MyTemplatePoint2.m b/wrap/tests/expected2/MyTemplatePoint2.m index 18c841b5d..235957963 100644 --- a/wrap/tests/expected2/MyTemplatePoint2.m +++ b/wrap/tests/expected2/MyTemplatePoint2.m @@ -83,7 +83,7 @@ classdef MyTemplatePoint2 < MyBase % RETURN_T usage: return_T(Point2 value) : returns gtsam::Point2 % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html if length(varargin) == 1 && isa(varargin{1},'gtsam.Point2') - geometry_wrapper(52, this, varargin{:}); + varargout{1} = geometry_wrapper(52, this, varargin{:}); else error('Arguments do not match any overload of function MyTemplatePoint2.return_T'); end @@ -93,7 +93,7 @@ classdef MyTemplatePoint2 < MyBase % RETURN_TPTR usage: return_Tptr(Point2 value) : returns gtsam::Point2 % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html if length(varargin) == 1 && isa(varargin{1},'gtsam.Point2') - geometry_wrapper(53, this, varargin{:}); + varargout{1} = geometry_wrapper(53, this, varargin{:}); else error('Arguments do not match any overload of function MyTemplatePoint2.return_Tptr'); end @@ -113,7 +113,7 @@ classdef MyTemplatePoint2 < MyBase % TEMPLATEDMETHODMATRIX usage: templatedMethodMatrix(Matrix t) : returns Matrix % 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') - geometry_wrapper(55, this, varargin{:}); + varargout{1} = geometry_wrapper(55, this, varargin{:}); else error('Arguments do not match any overload of function MyTemplatePoint2.templatedMethod'); end @@ -123,7 +123,7 @@ classdef MyTemplatePoint2 < MyBase % TEMPLATEDMETHODPOINT2 usage: templatedMethodPoint2(Point2 t) : returns gtsam::Point2 % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html if length(varargin) == 1 && isa(varargin{1},'gtsam.Point2') - geometry_wrapper(56, this, varargin{:}); + varargout{1} = geometry_wrapper(56, this, varargin{:}); else error('Arguments do not match any overload of function MyTemplatePoint2.templatedMethod'); end @@ -133,7 +133,7 @@ classdef MyTemplatePoint2 < MyBase % TEMPLATEDMETHODPOINT3 usage: templatedMethodPoint3(Point3 t) : returns gtsam::Point3 % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html if length(varargin) == 1 && isa(varargin{1},'gtsam.Point3') - geometry_wrapper(57, this, varargin{:}); + varargout{1} = geometry_wrapper(57, this, varargin{:}); else error('Arguments do not match any overload of function MyTemplatePoint2.templatedMethod'); end @@ -143,7 +143,7 @@ classdef MyTemplatePoint2 < MyBase % TEMPLATEDMETHODVECTOR usage: templatedMethodVector(Vector t) : returns Vector % 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') && size(varargin{1},2)==1 - geometry_wrapper(58, this, varargin{:}); + varargout{1} = geometry_wrapper(58, this, varargin{:}); else error('Arguments do not match any overload of function MyTemplatePoint2.templatedMethod'); end diff --git a/wrap/tests/expected2/MyTemplatePoint3.m b/wrap/tests/expected2/MyTemplatePoint3.m index fab352072..45fe34a0a 100644 --- a/wrap/tests/expected2/MyTemplatePoint3.m +++ b/wrap/tests/expected2/MyTemplatePoint3.m @@ -83,7 +83,7 @@ classdef MyTemplatePoint3 < MyBase % RETURN_T usage: return_T(Point3 value) : returns gtsam::Point3 % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html if length(varargin) == 1 && isa(varargin{1},'gtsam.Point3') - geometry_wrapper(67, this, varargin{:}); + varargout{1} = geometry_wrapper(67, this, varargin{:}); else error('Arguments do not match any overload of function MyTemplatePoint3.return_T'); end @@ -93,7 +93,7 @@ classdef MyTemplatePoint3 < MyBase % RETURN_TPTR usage: return_Tptr(Point3 value) : returns gtsam::Point3 % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html if length(varargin) == 1 && isa(varargin{1},'gtsam.Point3') - geometry_wrapper(68, this, varargin{:}); + varargout{1} = geometry_wrapper(68, this, varargin{:}); else error('Arguments do not match any overload of function MyTemplatePoint3.return_Tptr'); end @@ -113,7 +113,7 @@ classdef MyTemplatePoint3 < MyBase % TEMPLATEDMETHODMATRIX usage: templatedMethodMatrix(Matrix t) : returns Matrix % 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') - geometry_wrapper(70, this, varargin{:}); + varargout{1} = geometry_wrapper(70, this, varargin{:}); else error('Arguments do not match any overload of function MyTemplatePoint3.templatedMethod'); end @@ -123,7 +123,7 @@ classdef MyTemplatePoint3 < MyBase % TEMPLATEDMETHODPOINT2 usage: templatedMethodPoint2(Point2 t) : returns gtsam::Point2 % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html if length(varargin) == 1 && isa(varargin{1},'gtsam.Point2') - geometry_wrapper(71, this, varargin{:}); + varargout{1} = geometry_wrapper(71, this, varargin{:}); else error('Arguments do not match any overload of function MyTemplatePoint3.templatedMethod'); end @@ -133,7 +133,7 @@ classdef MyTemplatePoint3 < MyBase % TEMPLATEDMETHODPOINT3 usage: templatedMethodPoint3(Point3 t) : returns gtsam::Point3 % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html if length(varargin) == 1 && isa(varargin{1},'gtsam.Point3') - geometry_wrapper(72, this, varargin{:}); + varargout{1} = geometry_wrapper(72, this, varargin{:}); else error('Arguments do not match any overload of function MyTemplatePoint3.templatedMethod'); end @@ -143,7 +143,7 @@ classdef MyTemplatePoint3 < MyBase % TEMPLATEDMETHODVECTOR usage: templatedMethodVector(Vector t) : returns Vector % 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') && size(varargin{1},2)==1 - geometry_wrapper(73, this, varargin{:}); + varargout{1} = geometry_wrapper(73, this, varargin{:}); else error('Arguments do not match any overload of function MyTemplatePoint3.templatedMethod'); end diff --git a/wrap/tests/expected2/geometry_wrapper.cpp b/wrap/tests/expected2/geometry_wrapper.cpp index 9e6450d70..04e236426 100644 --- a/wrap/tests/expected2/geometry_wrapper.cpp +++ b/wrap/tests/expected2/geometry_wrapper.cpp @@ -685,20 +685,22 @@ void MyTemplatePoint2_templatedMethod_55(int nargout, mxArray *out[], int nargin void MyTemplatePoint2_templatedMethod_56(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { + typedef boost::shared_ptr SharedPoint2; typedef boost::shared_ptr Shared; checkArguments("templatedMethodPoint2",nargout,nargin-1,1); Shared obj = unwrap_shared_ptr(in[0], "ptr_MyTemplatePoint2"); gtsam::Point2& t = *unwrap_shared_ptr< gtsam::Point2 >(in[1], "ptr_gtsamPoint2"); - out[0] = wrap< gtsam::Point2 >(obj->templatedMethod(t)); + out[0] = wrap_shared_ptr(SharedPoint2(new gtsam::Point2(obj->templatedMethod(t))),"gtsam.Point2", false); } void MyTemplatePoint2_templatedMethod_57(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { + typedef boost::shared_ptr SharedPoint3; typedef boost::shared_ptr Shared; checkArguments("templatedMethodPoint3",nargout,nargin-1,1); Shared obj = unwrap_shared_ptr(in[0], "ptr_MyTemplatePoint2"); gtsam::Point3& t = *unwrap_shared_ptr< gtsam::Point3 >(in[1], "ptr_gtsamPoint3"); - out[0] = wrap< gtsam::Point3 >(obj->templatedMethod(t)); + out[0] = wrap_shared_ptr(SharedPoint3(new gtsam::Point3(obj->templatedMethod(t))),"gtsam.Point3", false); } void MyTemplatePoint2_templatedMethod_58(int nargout, mxArray *out[], int nargin, const mxArray *in[]) @@ -847,20 +849,22 @@ void MyTemplatePoint3_templatedMethod_70(int nargout, mxArray *out[], int nargin void MyTemplatePoint3_templatedMethod_71(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { + typedef boost::shared_ptr SharedPoint2; typedef boost::shared_ptr Shared; checkArguments("templatedMethodPoint2",nargout,nargin-1,1); Shared obj = unwrap_shared_ptr(in[0], "ptr_MyTemplatePoint3"); gtsam::Point2& t = *unwrap_shared_ptr< gtsam::Point2 >(in[1], "ptr_gtsamPoint2"); - out[0] = wrap< gtsam::Point2 >(obj->templatedMethod(t)); + out[0] = wrap_shared_ptr(SharedPoint2(new gtsam::Point2(obj->templatedMethod(t))),"gtsam.Point2", false); } void MyTemplatePoint3_templatedMethod_72(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { + typedef boost::shared_ptr SharedPoint3; typedef boost::shared_ptr Shared; checkArguments("templatedMethodPoint3",nargout,nargin-1,1); Shared obj = unwrap_shared_ptr(in[0], "ptr_MyTemplatePoint3"); gtsam::Point3& t = *unwrap_shared_ptr< gtsam::Point3 >(in[1], "ptr_gtsamPoint3"); - out[0] = wrap< gtsam::Point3 >(obj->templatedMethod(t)); + out[0] = wrap_shared_ptr(SharedPoint3(new gtsam::Point3(obj->templatedMethod(t))),"gtsam.Point3", false); } void MyTemplatePoint3_templatedMethod_73(int nargout, mxArray *out[], int nargin, const mxArray *in[]) From 7dbe9389cbb933a15169d27a1995f2f4f6d424ab Mon Sep 17 00:00:00 2001 From: dellaert Date: Mon, 1 Dec 2014 10:38:24 +0100 Subject: [PATCH 067/126] Fixed ArgumentListGrammar --- wrap/Argument.h | 3 ++- wrap/tests/testArgument.cpp | 16 ++++++++++++++++ 2 files changed, 18 insertions(+), 1 deletion(-) diff --git a/wrap/Argument.h b/wrap/Argument.h index 367d494c9..98a8ab7b1 100644 --- a/wrap/Argument.h +++ b/wrap/Argument.h @@ -173,7 +173,8 @@ struct ArgumentListGrammar: public classic::grammar { wrap::ArgumentList& result_; ///< successful parse will be placed in here - Argument arg, arg0; + const Argument arg0; // used to reset arg + mutable Argument arg; // temporary argument for use during parsing ArgumentGrammar argument_g; /// Construct type grammar and specify where result is placed diff --git a/wrap/tests/testArgument.cpp b/wrap/tests/testArgument.cpp index 31269c652..d99f9e4b3 100644 --- a/wrap/tests/testArgument.cpp +++ b/wrap/tests/testArgument.cpp @@ -95,16 +95,32 @@ TEST( ArgumentList, grammar ) { actual.clear(); EXPECT(parse("(char a)", g, space_p).full); + EXPECT_LONGS_EQUAL(1, actual.size()); + actual.clear(); EXPECT(parse("(unsigned char a)", g, space_p).full); + EXPECT_LONGS_EQUAL(1, actual.size()); + actual.clear(); EXPECT(parse("(Vector v, Matrix m)", g, space_p).full); + EXPECT_LONGS_EQUAL(2, actual.size()); + EXPECT(actual[0]==Argument(Qualified("Vector",Qualified::EIGEN),"v")); + EXPECT(actual[1]==Argument(Qualified("Matrix",Qualified::EIGEN),"m")); + actual.clear(); EXPECT(parse("(Point2 p)", g, space_p).full); + EXPECT_LONGS_EQUAL(1, actual.size()); + actual.clear(); EXPECT(parse("(Point2 p1, Point3 p2)", g, space_p).full); + EXPECT_LONGS_EQUAL(2, actual.size()); + EXPECT(actual[0]==Argument(Qualified("Point2"),"p1")); + EXPECT(actual[1]==Argument(Qualified("Point3"),"p2")); + actual.clear(); EXPECT(parse("(gtsam::Point2 p3)", g, space_p).full); + EXPECT_LONGS_EQUAL(1, actual.size()); + actual.clear(); } /* ************************************************************************* */ From e82752e269a1ec58126c48d3f01a0b9187880727 Mon Sep 17 00:00:00 2001 From: dellaert Date: Mon, 1 Dec 2014 10:47:42 +0100 Subject: [PATCH 068/126] Successful use of ArgumentListGrammar --- wrap/Module.cpp | 19 +++++++------------ 1 file changed, 7 insertions(+), 12 deletions(-) diff --git a/wrap/Module.cpp b/wrap/Module.cpp index 35a40c02d..e492a9ed0 100644 --- a/wrap/Module.cpp +++ b/wrap/Module.cpp @@ -157,16 +157,12 @@ void Module::parseMarkup(const std::string& data) { // NOTE: allows for pointers to all types ArgumentList args; - Argument arg,arg0; - ArgumentGrammar argument_g(arg); - Rule argument_p = argument_g[push_back_a(args, arg)][assign_a(arg, arg0)]; - - Rule argumentList_p = !argument_p >> * (',' >> argument_p); + ArgumentListGrammar argumentList_g(args); // parse class constructor Constructor constructor0(verbose), constructor(verbose); Rule constructor_p = - (basic.className_p >> '(' >> argumentList_p >> ')' >> ';' >> !basic.comments_p) + (basic.className_p >> argumentList_g >> ';' >> !basic.comments_p) [bl::bind(&Constructor::push_back, bl::var(constructor), bl::var(args))] [clear_a(args)]; @@ -184,7 +180,7 @@ void Module::parseMarkup(const std::string& data) { Rule method_p = !templateArgValues_p >> (returnValue_g >> methodName_p[assign_a(methodName)] >> - '(' >> argumentList_p >> ')' >> + argumentList_g >> !str_p("const")[assign_a(isConst,true)] >> ';' >> *basic.comments_p) [bl::bind(&Class::addMethod, bl::var(cls), verbose, bl::var(isConst), bl::var(methodName), bl::var(args), bl::var(retVal), @@ -198,7 +194,7 @@ void Module::parseMarkup(const std::string& data) { Rule static_method_p = (str_p("static") >> returnValue_g >> staticMethodName_p[assign_a(methodName)] >> - '(' >> argumentList_p >> ')' >> ';' >> *basic.comments_p) + argumentList_g >> ';' >> *basic.comments_p) [bl::bind(&StaticMethod::addOverload, bl::var(cls.static_methods)[bl::var(methodName)], bl::var(methodName), bl::var(args), bl::var(retVal), boost::none,verbose)] @@ -242,7 +238,7 @@ void Module::parseMarkup(const std::string& data) { Qualified globalFunction; Rule global_function_p = (returnValue_g >> staticMethodName_p[assign_a(globalFunction.name_)] >> - '(' >> argumentList_p >> ')' >> ';' >> *basic.comments_p) + argumentList_g >> ';' >> *basic.comments_p) [assign_a(globalFunction.namespaces_,namespaces)] [bl::bind(&GlobalFunction::addOverload, bl::var(global_functions)[bl::var(globalFunction.name_)], @@ -295,7 +291,7 @@ void Module::parseMarkup(const std::string& data) { BOOST_SPIRIT_DEBUG_NODE(basisType_p); BOOST_SPIRIT_DEBUG_NODE(name_p); BOOST_SPIRIT_DEBUG_NODE(argument_p); - BOOST_SPIRIT_DEBUG_NODE(argumentList_p); + BOOST_SPIRIT_DEBUG_NODE(argumentList_g); BOOST_SPIRIT_DEBUG_NODE(constructor_p); BOOST_SPIRIT_DEBUG_NODE(returnType1_p); BOOST_SPIRIT_DEBUG_NODE(returnType2_p); @@ -316,8 +312,7 @@ void Module::parseMarkup(const std::string& data) { printf("parsing stopped at \n%.20s\n",info.stop); cout << "Stopped near:\n" "class '" << cls.name_ << "'\n" - "method '" << methodName << "'\n" - "argument '" << arg.name << "'" << endl; + "method '" << methodName << "'" << endl; throw ParseFailed((int)info.length); } From 3c97c33755e47399d9ebf53bc13784fc0bf05265 Mon Sep 17 00:00:00 2001 From: dellaert Date: Mon, 1 Dec 2014 11:25:16 +0100 Subject: [PATCH 069/126] Fixed test --- matlab/gtsam_tests/testValues.m | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/matlab/gtsam_tests/testValues.m b/matlab/gtsam_tests/testValues.m index ce2ae9d7e..fe2cd30fe 100644 --- a/matlab/gtsam_tests/testValues.m +++ b/matlab/gtsam_tests/testValues.m @@ -35,6 +35,6 @@ EXPECT('at',values.atConstantBias(10).equals(imuBias.ConstantBias,tol)); % special cases for Vector and Matrix: actualVector = values.atVector(11); -EQUALITY('at',[1 2;3 4],actualVector,tol); +EQUALITY('at',[1;2;3],actualVector,tol); actualMatrix = values.atMatrix(12); EQUALITY('at',[1 2;3 4],actualMatrix,tol); From d25636685ba44f5d98a498983105fd5a4aca8e58 Mon Sep 17 00:00:00 2001 From: dellaert Date: Mon, 1 Dec 2014 11:32:33 +0100 Subject: [PATCH 070/126] TypeListGrammar --- wrap/tests/testType.cpp | 85 +++++++++++++++++++++++++++++++++++++++++ 1 file changed, 85 insertions(+) diff --git a/wrap/tests/testType.cpp b/wrap/tests/testType.cpp index abf3cf65f..7f165b109 100644 --- a/wrap/tests/testType.cpp +++ b/wrap/tests/testType.cpp @@ -83,6 +83,91 @@ TEST( Type, grammar ) { actual.clear(); } +/* ************************************************************************* */ +// http://boost-spirit.com/distrib/spirit_1_8_2/libs/spirit/doc/grammar.html +struct TypeListGrammar: public classic::grammar { + + typedef std::vector TypeList; + TypeList& result_; ///< successful parse will be placed in here + + mutable wrap::Qualified type; // temporary type for use during parsing + TypeGrammar type_g; + + /// Construct type grammar and specify where result is placed + TypeListGrammar(TypeList& result) : + result_(result), type_g(type) { + } + + /// Definition of type grammar + template + struct definition: basic_rules { + + typedef classic::rule Rule; + + Rule type_p, typeList_p; + + definition(TypeListGrammar const& self) { + using namespace classic; + type_p = self.type_g // + [classic::push_back_a(self.result_, self.type)] // + [clear_a(self.type)]; + typeList_p = '{' >> !type_p >> *(',' >> type_p) >> '}'; + } + + Rule const& start() const { + return typeList_p; + } + + }; +}; +// TypeListGrammar + +//****************************************************************************** +TEST( TypeList, grammar ) { + + using classic::space_p; + + // Create type grammar that will place result in actual + vector actual; + TypeListGrammar g(actual); + + EXPECT(parse("{gtsam::Point2}", g, space_p).full); + EXPECT_LONGS_EQUAL(1, actual.size()); + actual.clear(); + + EXPECT(parse("{}", g, space_p).full); + EXPECT_LONGS_EQUAL(0, actual.size()); + actual.clear(); + + EXPECT(parse("{char}", g, space_p).full); + EXPECT_LONGS_EQUAL(1, actual.size()); + actual.clear(); + + EXPECT(parse("{unsigned char}", g, space_p).full); + EXPECT_LONGS_EQUAL(1, actual.size()); + actual.clear(); + + EXPECT(parse("{Vector, Matrix}", g, space_p).full); + EXPECT_LONGS_EQUAL(2, actual.size()); + EXPECT(actual[0]==Qualified("Vector",Qualified::EIGEN)); + EXPECT(actual[1]==Qualified("Matrix",Qualified::EIGEN)); + actual.clear(); + + EXPECT(parse("{Point2}", g, space_p).full); + EXPECT_LONGS_EQUAL(1, actual.size()); + actual.clear(); + + EXPECT(parse("{Point2, Point3}", g, space_p).full); + EXPECT_LONGS_EQUAL(2, actual.size()); + EXPECT(actual[0]==Qualified("Point2")); + EXPECT(actual[1]==Qualified("Point3")); + actual.clear(); + + EXPECT(parse("{gtsam::Point2}", g, space_p).full); + EXPECT_LONGS_EQUAL(1, actual.size()); + actual.clear(); +} + //****************************************************************************** int main() { TestResult tr; From 19ea0436dbf82d7c0d72e347a84b2b6915c8f85a Mon Sep 17 00:00:00 2001 From: dellaert Date: Mon, 1 Dec 2014 11:35:48 +0100 Subject: [PATCH 071/126] Moved to header --- wrap/Qualified.h | 43 +++++++++++++++++++++++++++++++++++++++++ wrap/tests/testType.cpp | 39 ------------------------------------- 2 files changed, 43 insertions(+), 39 deletions(-) diff --git a/wrap/Qualified.h b/wrap/Qualified.h index 494d6b0ff..6a5a3e9ce 100644 --- a/wrap/Qualified.h +++ b/wrap/Qualified.h @@ -161,6 +161,8 @@ public: }; +/* ************************************************************************* */ +/// Som basic rules used by all parsers template struct basic_rules { @@ -194,6 +196,7 @@ struct basic_rules { } }; +/* ************************************************************************* */ // http://boost-spirit.com/distrib/spirit_1_8_2/libs/spirit/doc/grammar.html class TypeGrammar: public classic::grammar { @@ -255,6 +258,46 @@ public: }; // type_grammar +/* ************************************************************************* */ +// http://boost-spirit.com/distrib/spirit_1_8_2/libs/spirit/doc/grammar.html +struct TypeListGrammar: public classic::grammar { + + typedef std::vector TypeList; + TypeList& result_; ///< successful parse will be placed in here + + mutable wrap::Qualified type; // temporary type for use during parsing + TypeGrammar type_g; + + /// Construct type grammar and specify where result is placed + TypeListGrammar(TypeList& result) : + result_(result), type_g(type) { + } + + /// Definition of type grammar + template + struct definition: basic_rules { + + typedef classic::rule Rule; + + Rule type_p, typeList_p; + + definition(TypeListGrammar const& self) { + using namespace classic; + type_p = self.type_g // + [classic::push_back_a(self.result_, self.type)] // + [clear_a(self.type)]; + typeList_p = '{' >> !type_p >> *(',' >> type_p) >> '}'; + } + + Rule const& start() const { + return typeList_p; + } + + }; +}; +// TypeListGrammar + +/* ************************************************************************* */ // Needed for other parsers in Argument.h and ReturnType.h static const bool T = true; diff --git a/wrap/tests/testType.cpp b/wrap/tests/testType.cpp index 7f165b109..1b55a1bb3 100644 --- a/wrap/tests/testType.cpp +++ b/wrap/tests/testType.cpp @@ -83,45 +83,6 @@ TEST( Type, grammar ) { actual.clear(); } -/* ************************************************************************* */ -// http://boost-spirit.com/distrib/spirit_1_8_2/libs/spirit/doc/grammar.html -struct TypeListGrammar: public classic::grammar { - - typedef std::vector TypeList; - TypeList& result_; ///< successful parse will be placed in here - - mutable wrap::Qualified type; // temporary type for use during parsing - TypeGrammar type_g; - - /// Construct type grammar and specify where result is placed - TypeListGrammar(TypeList& result) : - result_(result), type_g(type) { - } - - /// Definition of type grammar - template - struct definition: basic_rules { - - typedef classic::rule Rule; - - Rule type_p, typeList_p; - - definition(TypeListGrammar const& self) { - using namespace classic; - type_p = self.type_g // - [classic::push_back_a(self.result_, self.type)] // - [clear_a(self.type)]; - typeList_p = '{' >> !type_p >> *(',' >> type_p) >> '}'; - } - - Rule const& start() const { - return typeList_p; - } - - }; -}; -// TypeListGrammar - //****************************************************************************** TEST( TypeList, grammar ) { From 4d1225cda798f26e281c6748b08492e45a0885c2 Mon Sep 17 00:00:00 2001 From: dellaert Date: Mon, 1 Dec 2014 11:43:19 +0100 Subject: [PATCH 072/126] Moved basic parsers to new header file spirit.h --- wrap/Module.cpp | 2 +- wrap/Qualified.h | 46 ++---------------------------- wrap/{spirit_actors.h => spirit.h} | 45 +++++++++++++++++++++++++++-- 3 files changed, 46 insertions(+), 47 deletions(-) rename wrap/{spirit_actors.h => spirit.h} (69%) diff --git a/wrap/Module.cpp b/wrap/Module.cpp index e492a9ed0..b31ea2b12 100644 --- a/wrap/Module.cpp +++ b/wrap/Module.cpp @@ -23,7 +23,7 @@ #include "utilities.h" //#define BOOST_SPIRIT_DEBUG -#include "spirit_actors.h" +#include "spirit.h" #ifdef __GNUC__ #pragma GCC diagnostic push diff --git a/wrap/Qualified.h b/wrap/Qualified.h index 6a5a3e9ce..0466b10f3 100644 --- a/wrap/Qualified.h +++ b/wrap/Qualified.h @@ -18,14 +18,7 @@ #pragma once -#include -#include -#include -#include -#include - -namespace classic = BOOST_SPIRIT_CLASSIC_NS; - +#include #include #include @@ -161,41 +154,6 @@ public: }; -/* ************************************************************************* */ -/// Som basic rules used by all parsers -template -struct basic_rules { - - typedef classic::rule Rule; - - Rule comments_p, basisType_p, eigenType_p, keywords_p, stlType_p, name_p, - className_p, namespace_p; - - basic_rules() { - - using namespace classic; - - comments_p = comment_p("/*", "*/") | comment_p("//", eol_p); - - basisType_p = (str_p("string") | "bool" | "size_t" | "int" | "double" - | "char" | "unsigned char"); - - eigenType_p = (str_p("Vector") | "Matrix"); - - keywords_p = - (str_p("const") | "static" | "namespace" | "void" | basisType_p); - - stlType_p = (str_p("vector") | "list"); - - name_p = lexeme_d[alpha_p >> *(alnum_p | '_')]; - - className_p = (lexeme_d[upper_p >> *(alnum_p | '_')] - eigenType_p - - keywords_p) | stlType_p; - - namespace_p = lexeme_d[lower_p >> *(alnum_p | '_')] - keywords_p; - } -}; - /* ************************************************************************* */ // http://boost-spirit.com/distrib/spirit_1_8_2/libs/spirit/doc/grammar.html class TypeGrammar: public classic::grammar { @@ -284,7 +242,7 @@ struct TypeListGrammar: public classic::grammar { definition(TypeListGrammar const& self) { using namespace classic; type_p = self.type_g // - [classic::push_back_a(self.result_, self.type)] // + [push_back_a(self.result_, self.type)] // [clear_a(self.type)]; typeList_p = '{' >> !type_p >> *(',' >> type_p) >> '}'; } diff --git a/wrap/spirit_actors.h b/wrap/spirit.h similarity index 69% rename from wrap/spirit_actors.h rename to wrap/spirit.h index ed7558b78..4a18b53e8 100644 --- a/wrap/spirit_actors.h +++ b/wrap/spirit.h @@ -1,16 +1,20 @@ /** * @file spirit_actors.h * - * @brief Additional actors for the wrap parser + * @brief Additional utilities and actors for the wrap parser * * @date Dec 8, 2011 * @author Alex Cunningham + * @author Frank Dellaert */ #pragma once #include -#include +#include +#include +#include +#include namespace boost { namespace spirit { @@ -121,3 +125,40 @@ BOOST_SPIRIT_CLASSIC_NAMESPACE_END } } +namespace classic = BOOST_SPIRIT_CLASSIC_NS; + +/// Some basic rules used by all parsers +template +struct basic_rules { + + typedef BOOST_SPIRIT_CLASSIC_NS::rule Rule; + + Rule comments_p, basisType_p, eigenType_p, keywords_p, stlType_p, name_p, + className_p, namespace_p; + + basic_rules() { + + using namespace BOOST_SPIRIT_CLASSIC_NS; + + comments_p = comment_p("/*", "*/") | comment_p("//", eol_p); + + basisType_p = (str_p("string") | "bool" | "size_t" | "int" | "double" + | "char" | "unsigned char"); + + eigenType_p = (str_p("Vector") | "Matrix"); + + keywords_p = + (str_p("const") | "static" | "namespace" | "void" | basisType_p); + + stlType_p = (str_p("vector") | "list"); + + name_p = lexeme_d[alpha_p >> *(alnum_p | '_')]; + + className_p = (lexeme_d[upper_p >> *(alnum_p | '_')] - eigenType_p + - keywords_p) | stlType_p; + + namespace_p = lexeme_d[lower_p >> *(alnum_p | '_')] - keywords_p; + } +}; + + From 9a770726549d2a0fa435ef82175a64b69a488b9f Mon Sep 17 00:00:00 2001 From: dellaert Date: Mon, 1 Dec 2014 12:14:08 +0100 Subject: [PATCH 073/126] Successfully used TypeListGrammar --- wrap/Module.cpp | 20 +++++--------------- wrap/Qualified.h | 5 +++-- wrap/tests/testType.cpp | 2 +- 3 files changed, 9 insertions(+), 18 deletions(-) diff --git a/wrap/Module.cpp b/wrap/Module.cpp index b31ea2b12..a94fb59b9 100644 --- a/wrap/Module.cpp +++ b/wrap/Module.cpp @@ -114,35 +114,25 @@ void Module::parseMarkup(const std::string& data) { // TODO, do we really need cls here? Non-local Class cls0(verbose),cls(verbose); - // parse "gtsam::Pose2" and add to templateArgValues - Qualified templateArgValue; - vector templateArgValues; - TypeGrammar templateArgValue_g(templateArgValue); - Rule templateArgValue_p = templateArgValue_g - [push_back_a(templateArgValues, templateArgValue)] - [clear_a(templateArgValue)]; - // template string templateArgName; + vector templateArgValues; + TypeListGrammar<'{','}'> templateArgValues_g(templateArgValues); Rule templateArgValues_p = (str_p("template") >> '<' >> basic.name_p[assign_a(templateArgName)] >> '=' >> - '{' >> !(templateArgValue_p >> *(',' >> templateArgValue_p)) >> '}' >> - '>'); + templateArgValues_g >> '>'); // parse "gtsam::Pose2" and add to singleInstantiation.typeList TemplateInstantiationTypedef singleInstantiation, singleInstantiation0; - Rule templateSingleInstantiationArg_p = templateArgValue_g - [push_back_a(singleInstantiation.typeList, templateArgValue)] - [clear_a(templateArgValue)]; + TypeListGrammar<'<','>'> typelist_g(singleInstantiation.typeList); // typedef gtsam::RangeFactor RangeFactorPosePoint2; vector namespaces; // current namespace tag TypeGrammar instantiationClass_g(singleInstantiation.class_); Rule templateSingleInstantiation_p = (str_p("typedef") >> instantiationClass_g >> - '<' >> templateSingleInstantiationArg_p >> *(',' >> templateSingleInstantiationArg_p) >> - '>' >> + typelist_g >> basic.className_p[assign_a(singleInstantiation.name_)] >> ';') [assign_a(singleInstantiation.namespaces_, namespaces)] diff --git a/wrap/Qualified.h b/wrap/Qualified.h index 0466b10f3..29b961518 100644 --- a/wrap/Qualified.h +++ b/wrap/Qualified.h @@ -218,7 +218,8 @@ public: /* ************************************************************************* */ // http://boost-spirit.com/distrib/spirit_1_8_2/libs/spirit/doc/grammar.html -struct TypeListGrammar: public classic::grammar { +template +struct TypeListGrammar: public classic::grammar > { typedef std::vector TypeList; TypeList& result_; ///< successful parse will be placed in here @@ -244,7 +245,7 @@ struct TypeListGrammar: public classic::grammar { type_p = self.type_g // [push_back_a(self.result_, self.type)] // [clear_a(self.type)]; - typeList_p = '{' >> !type_p >> *(',' >> type_p) >> '}'; + typeList_p = OPEN >> !type_p >> *(',' >> type_p) >> CLOSE; } Rule const& start() const { diff --git a/wrap/tests/testType.cpp b/wrap/tests/testType.cpp index 1b55a1bb3..f06a88962 100644 --- a/wrap/tests/testType.cpp +++ b/wrap/tests/testType.cpp @@ -90,7 +90,7 @@ TEST( TypeList, grammar ) { // Create type grammar that will place result in actual vector actual; - TypeListGrammar g(actual); + TypeListGrammar<'{','}'> g(actual); EXPECT(parse("{gtsam::Point2}", g, space_p).full); EXPECT_LONGS_EQUAL(1, actual.size()); From 32852eeec7deb649bc274e8005613bdc9206a8b6 Mon Sep 17 00:00:00 2001 From: dellaert Date: Mon, 1 Dec 2014 12:43:12 +0100 Subject: [PATCH 074/126] Template class and parser --- .cproject | 106 +++++++++++++++++++++--------------- wrap/Template.h | 72 ++++++++++++++++++++++++ wrap/tests/testTemplate.cpp | 56 +++++++++++++++++++ 3 files changed, 190 insertions(+), 44 deletions(-) create mode 100644 wrap/Template.h create mode 100644 wrap/tests/testTemplate.cpp diff --git a/.cproject b/.cproject index b0eb31888..4649fd973 100644 --- a/.cproject +++ b/.cproject @@ -592,6 +592,7 @@ make + tests/testBayesTree.run true false @@ -599,6 +600,7 @@ make + testBinaryBayesNet.run true false @@ -646,6 +648,7 @@ make + testSymbolicBayesNet.run true false @@ -653,6 +656,7 @@ make + tests/testSymbolicFactor.run true false @@ -660,6 +664,7 @@ make + testSymbolicFactorGraph.run true false @@ -675,6 +680,7 @@ make + tests/testBayesTree true false @@ -1122,6 +1128,7 @@ make + testErrors.run true false @@ -1351,6 +1358,46 @@ true true + + make + -j5 + testBTree.run + true + true + true + + + make + -j5 + testDSF.run + true + true + true + + + make + -j5 + testDSFMap.run + true + true + true + + + make + -j5 + testDSFVector.run + true + true + true + + + make + -j5 + testFixedVector.run + true + true + true + make -j2 @@ -1433,7 +1480,6 @@ make - testSimulated2DOriented.run true false @@ -1473,7 +1519,6 @@ make - testSimulated2D.run true false @@ -1481,7 +1526,6 @@ make - testSimulated3D.run true false @@ -1495,46 +1539,6 @@ true true - - make - -j5 - testBTree.run - true - true - true - - - make - -j5 - testDSF.run - true - true - true - - - make - -j5 - testDSFMap.run - true - true - true - - - make - -j5 - testDSFVector.run - true - true - true - - - make - -j5 - testFixedVector.run - true - true - true - make -j5 @@ -1792,6 +1796,7 @@ cpack + -G DEB true false @@ -1799,6 +1804,7 @@ cpack + -G RPM true false @@ -1806,6 +1812,7 @@ cpack + -G TGZ true false @@ -1813,6 +1820,7 @@ cpack + --config CPackSourceConfig.cmake true false @@ -2417,6 +2425,14 @@ true true + + make + -j4 + testTemplate.run + true + true + true + make -j5 @@ -2651,6 +2667,7 @@ make + testGraph.run true false @@ -2658,6 +2675,7 @@ make + testJunctionTree.run true false @@ -2665,6 +2683,7 @@ make + testSymbolicBayesNetB.run true false @@ -3200,7 +3219,6 @@ make - tests/testGaussianISAM2 true false diff --git a/wrap/Template.h b/wrap/Template.h new file mode 100644 index 000000000..c9edcaf2b --- /dev/null +++ b/wrap/Template.h @@ -0,0 +1,72 @@ +/* ---------------------------------------------------------------------------- + + * GTSAM Copyright 2010, Georgia Tech Research Corporation, + * Atlanta, Georgia 30332-0415 + * All Rights Reserved + * Authors: Frank Dellaert, et al. (see THANKS for the full author list) + + * See LICENSE for the license information + + * -------------------------------------------------------------------------- */ + +/** + * @file Template.h + * @brief Template name + * @author Frank Dellaert + * @date Nov 11, 2014 + **/ + +#pragma once + +#include + +namespace wrap { + +/// The template specification that goes before a method or a class +struct Template { + std::string argName; + std::vector argValues; + void clear() { + argName.clear(); + argValues.clear(); + } +}; + +/* ************************************************************************* */ +// http://boost-spirit.com/distrib/spirit_1_8_2/libs/spirit/doc/grammar.html +struct TemplateGrammar: public classic::grammar { + + Template& result_; ///< successful parse will be placed in here + + TypeListGrammar<'{', '}'> argValues_g; + + /// Construct type grammar and specify where result is placed + TemplateGrammar(Template& result) : + result_(result), argValues_g(result.argValues) { + } + + /// Definition of type grammar + template + struct definition: basic_rules { + + typedef classic::rule Rule; + + Rule templateArgValues_p; + + definition(TemplateGrammar const& self) { + using namespace classic; + templateArgValues_p = (str_p("template") >> '<' + >> (basic_rules::name_p)[assign_a(self.result_.argName)] + >> '=' >> self.argValues_g >> '>'); + } + + Rule const& start() const { + return templateArgValues_p; + } + + }; +}; +// TemplateGrammar + +}// \namespace wrap + diff --git a/wrap/tests/testTemplate.cpp b/wrap/tests/testTemplate.cpp new file mode 100644 index 000000000..b1f3ce544 --- /dev/null +++ b/wrap/tests/testTemplate.cpp @@ -0,0 +1,56 @@ +/* ---------------------------------------------------------------------------- + + * GTSAM Copyright 2010, Georgia Tech Research Corporation, + * Atlanta, Georgia 30332-0415 + * All Rights Reserved + * Authors: Frank Dellaert, et al. (see THANKS for the full author list) + + * See LICENSE for the license information + + * -------------------------------------------------------------------------- */ + +/** + * @file testTemplate.cpp + * @brief unit test for Template class + * @author Frank Dellaert + * @date Dec 1, 2014 + **/ + +#include +#include + +using namespace std; +using namespace wrap; + +//****************************************************************************** +TEST( Template, grammar ) { + + using classic::space_p; + + // Create type grammar that will place result in actual + Template actual; + TemplateGrammar g(actual); + + EXPECT(parse("template", g, space_p).full); + EXPECT_LONGS_EQUAL(2, actual.argValues.size()); + EXPECT(actual.argName=="T"); + EXPECT(actual.argValues[0]==Qualified("gtsam","Point2",Qualified::CLASS)); + EXPECT(actual.argValues[1]==Qualified("Matrix",Qualified::EIGEN)); + actual.clear(); + + EXPECT(parse("template", g, space_p).full); + EXPECT_LONGS_EQUAL(4, actual.argValues.size()); + EXPECT(actual.argName=="ARG"); + EXPECT(actual.argValues[0]==Qualified("gtsam","Point2",Qualified::CLASS)); + EXPECT(actual.argValues[1]==Qualified("gtsam","Point3",Qualified::CLASS)); + EXPECT(actual.argValues[2]==Qualified("Vector",Qualified::EIGEN)); + EXPECT(actual.argValues[3]==Qualified("Matrix",Qualified::EIGEN)); + actual.clear(); +} + +//****************************************************************************** +int main() { + TestResult tr; + return TestRegistry::runAllTests(tr); +} +//****************************************************************************** From 8eb6393c926535e163d8ccb2696998b439a4743d Mon Sep 17 00:00:00 2001 From: dellaert Date: Mon, 1 Dec 2014 14:35:02 +0100 Subject: [PATCH 075/126] Using TemplateGrammar --- wrap/Class.cpp | 15 ++++++++------- wrap/Class.h | 3 ++- wrap/Module.cpp | 35 ++++++++++++++++------------------- 3 files changed, 26 insertions(+), 27 deletions(-) diff --git a/wrap/Class.cpp b/wrap/Class.cpp index bb8051093..09433d616 100644 --- a/wrap/Class.cpp +++ b/wrap/Class.cpp @@ -43,7 +43,8 @@ void Class::assignParent(const Qualified& parent) { /* ************************************************************************* */ boost::optional Class::qualifiedParent() const { boost::optional result = boost::none; - if (parentClass) result = parentClass->qualifiedName("::"); + if (parentClass) + result = parentClass->qualifiedName("::"); return result; } @@ -61,7 +62,7 @@ Method& Class::mutableMethod(Str key) { try { return methods_.at(key); } catch (const out_of_range& oor) { - handleException(oor,methods_); + handleException(oor, methods_); throw runtime_error("Internal error in wrap"); } } @@ -71,7 +72,7 @@ const Method& Class::method(Str key) const { try { return methods_.at(key); } catch (const out_of_range& oor) { - handleException(oor,methods_); + handleException(oor, methods_); throw runtime_error("Internal error in wrap"); } } @@ -316,13 +317,13 @@ vector Class::expandTemplate(Str templateArg, /* ************************************************************************* */ void Class::addMethod(bool verbose, bool is_const, Str methodName, const ArgumentList& argumentList, const ReturnValue& returnValue, - Str templateArgName, const vector& templateArgValues) { + const Template& tmplate) { // Check if templated - if (!templateArgName.empty() && templateArgValues.size() > 0) { + if (!tmplate.argName.empty() && tmplate.argValues.size() > 0) { // Create method to expand // For all values of the template argument, create a new method - BOOST_FOREACH(const Qualified& instName, templateArgValues) { - const TemplateSubstitution ts(templateArgName, instName, *this); + BOOST_FOREACH(const Qualified& instName, tmplate.argValues) { + const TemplateSubstitution ts(tmplate.argName, instName, *this); // substitute template in arguments ArgumentList expandedArgs = argumentList.expandTemplate(ts); // do the same for return type diff --git a/wrap/Class.h b/wrap/Class.h index 449f3df4b..8faf7ab77 100644 --- a/wrap/Class.h +++ b/wrap/Class.h @@ -19,6 +19,7 @@ #pragma once +#include "Template.h" #include "Constructor.h" #include "Deconstructor.h" #include "Method.h" @@ -95,7 +96,7 @@ public: /// Add potentially overloaded, potentially templated method void addMethod(bool verbose, bool is_const, Str methodName, const ArgumentList& argumentList, const ReturnValue& returnValue, - Str templateArgName, const std::vector& templateArgValues); + const Template& tmplate); /// Post-process classes for serialization markers void erase_serialization(); // non-const ! diff --git a/wrap/Module.cpp b/wrap/Module.cpp index a94fb59b9..d7059d316 100644 --- a/wrap/Module.cpp +++ b/wrap/Module.cpp @@ -114,15 +114,6 @@ void Module::parseMarkup(const std::string& data) { // TODO, do we really need cls here? Non-local Class cls0(verbose),cls(verbose); - // template - string templateArgName; - vector templateArgValues; - TypeListGrammar<'{','}'> templateArgValues_g(templateArgValues); - Rule templateArgValues_p = - (str_p("template") >> - '<' >> basic.name_p[assign_a(templateArgName)] >> '=' >> - templateArgValues_g >> '>'); - // parse "gtsam::Pose2" and add to singleInstantiation.typeList TemplateInstantiationTypedef singleInstantiation, singleInstantiation0; TypeListGrammar<'<','>'> typelist_g(singleInstantiation.typeList); @@ -164,20 +155,24 @@ void Module::parseMarkup(const std::string& data) { Rule methodName_p = lexeme_d[(upper_p | lower_p) >> *(alnum_p | '_')]; + // template + Template methodTemplate; + TemplateGrammar methodTemplate_g(methodTemplate); + // gtsam::Values retract(const gtsam::VectorValues& delta) const; string methodName; bool isConst, isConst0 = false; Rule method_p = - !templateArgValues_p >> + !methodTemplate_g >> (returnValue_g >> methodName_p[assign_a(methodName)] >> argumentList_g >> !str_p("const")[assign_a(isConst,true)] >> ';' >> *basic.comments_p) [bl::bind(&Class::addMethod, bl::var(cls), verbose, bl::var(isConst), bl::var(methodName), bl::var(args), bl::var(retVal), - bl::var(templateArgName), bl::var(templateArgValues))] + bl::var(methodTemplate))] [assign_a(retVal,retVal0)] [clear_a(args)] - [clear_a(templateArgValues)] + [clear_a(methodTemplate)] [assign_a(isConst,isConst0)]; Rule staticMethodName_p = lexeme_d[(upper_p | lower_p) >> *(alnum_p | '_')]; @@ -193,17 +188,19 @@ void Module::parseMarkup(const std::string& data) { Rule functions_p = constructor_p | method_p | static_method_p; + // template + Template classTemplate; + TemplateGrammar classTemplate_g(classTemplate); + + // Parent class Qualified possibleParent; TypeGrammar classParent_p(possibleParent); // parse a full class - vector templateInstantiations; Rule class_p = eps_p[assign_a(cls,cls0)] - >> (!(templateArgValues_p - [push_back_a(cls.templateArgs, templateArgName)] - [assign_a(templateInstantiations,templateArgValues)] - [clear_a(templateArgValues)] + >> (!(classTemplate_g + [push_back_a(cls.templateArgs, classTemplate.argName)] | templateList_p) >> !(str_p("virtual")[assign_a(cls.isVirtual, true)]) >> str_p("class") @@ -219,8 +216,8 @@ void Module::parseMarkup(const std::string& data) { [assign_a(cls.namespaces_, namespaces)] [assign_a(cls.deconstructor.name,cls.name_)] [bl::bind(&handle_possible_template, bl::var(classes), bl::var(cls), - bl::var(templateInstantiations))] - [clear_a(templateInstantiations)] + bl::var(classTemplate.argValues))] + [clear_a(classTemplate)] [assign_a(constructor, constructor0)] [assign_a(cls,cls0)]; From 8d128ef809e6a260deea27066dc046e708c3f369 Mon Sep 17 00:00:00 2001 From: dellaert Date: Mon, 1 Dec 2014 14:42:19 +0100 Subject: [PATCH 076/126] Make sure an Eigen type is tested as template parameter --- wrap/ReturnType.cpp | 4 +- wrap/tests/expected2/MyTemplateMatrix.m | 156 +++++++++++++++++ wrap/tests/expected2/geometry_wrapper.cpp | 204 ++++++++++++---------- wrap/tests/geometry.h | 2 +- 4 files changed, 266 insertions(+), 100 deletions(-) create mode 100644 wrap/tests/expected2/MyTemplateMatrix.m diff --git a/wrap/ReturnType.cpp b/wrap/ReturnType.cpp index 9c046ba46..41fd51680 100644 --- a/wrap/ReturnType.cpp +++ b/wrap/ReturnType.cpp @@ -46,10 +46,10 @@ void ReturnType::wrap_result(const string& out, const string& result, } else if (isPtr) { // Handle shared pointer case for BASIS/EIGEN/VOID - wrapperFile.oss << "{\n Shared" << name() << "* ret = new Shared" << name() + wrapperFile.oss << " {\n Shared" << name() << "* ret = new Shared" << name() << "(" << result << ");" << endl; wrapperFile.oss << out << " = wrap_shared_ptr(ret,\"" << matlabType - << "\");\n}\n"; + << "\");\n }\n"; } else if (matlabType != "void") diff --git a/wrap/tests/expected2/MyTemplateMatrix.m b/wrap/tests/expected2/MyTemplateMatrix.m new file mode 100644 index 000000000..977660a15 --- /dev/null +++ b/wrap/tests/expected2/MyTemplateMatrix.m @@ -0,0 +1,156 @@ +%class MyTemplateMatrix, see Doxygen page for details +%at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html +% +%-------Constructors------- +%MyTemplateMatrix() +% +%-------Methods------- +%accept_T(Matrix value) : returns void +%accept_Tptr(Matrix value) : returns void +%create_MixedPtrs() : returns pair< Matrix, Matrix > +%create_ptrs() : returns pair< Matrix, Matrix > +%return_T(Matrix value) : returns Matrix +%return_Tptr(Matrix value) : returns Matrix +%return_ptrs(Matrix p1, Matrix p2) : returns pair< Matrix, Matrix > +%templatedMethodMatrix(Matrix t) : returns Matrix +%templatedMethodPoint2(Point2 t) : returns gtsam::Point2 +%templatedMethodPoint3(Point3 t) : returns gtsam::Point3 +%templatedMethodVector(Vector t) : returns Vector +% +classdef MyTemplateMatrix < MyBase + properties + ptr_MyTemplateMatrix = 0 + end + methods + function obj = MyTemplateMatrix(varargin) + if (nargin == 2 || (nargin == 3 && strcmp(varargin{3}, 'void'))) && isa(varargin{1}, 'uint64') && varargin{1} == uint64(5139824614673773682) + if nargin == 2 + my_ptr = varargin{2}; + else + my_ptr = geometry_wrapper(60, varargin{2}); + end + base_ptr = geometry_wrapper(59, my_ptr); + elseif nargin == 0 + [ my_ptr, base_ptr ] = geometry_wrapper(61); + else + error('Arguments do not match any overload of MyTemplateMatrix constructor'); + end + obj = obj@MyBase(uint64(5139824614673773682), base_ptr); + obj.ptr_MyTemplateMatrix = my_ptr; + end + + function delete(obj) + geometry_wrapper(62, obj.ptr_MyTemplateMatrix); + 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 = accept_T(this, varargin) + % ACCEPT_T usage: accept_T(Matrix value) : returns void + % 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') + geometry_wrapper(63, this, varargin{:}); + else + error('Arguments do not match any overload of function MyTemplateMatrix.accept_T'); + end + end + + function varargout = accept_Tptr(this, varargin) + % ACCEPT_TPTR usage: accept_Tptr(Matrix value) : returns void + % 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') + geometry_wrapper(64, this, varargin{:}); + else + error('Arguments do not match any overload of function MyTemplateMatrix.accept_Tptr'); + end + end + + function varargout = create_MixedPtrs(this, varargin) + % CREATE_MIXEDPTRS usage: create_MixedPtrs() : returns pair< Matrix, Matrix > + % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html + [ varargout{1} varargout{2} ] = geometry_wrapper(65, this, varargin{:}); + end + + function varargout = create_ptrs(this, varargin) + % CREATE_PTRS usage: create_ptrs() : returns pair< Matrix, Matrix > + % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html + [ varargout{1} varargout{2} ] = geometry_wrapper(66, this, varargin{:}); + end + + function varargout = return_T(this, varargin) + % RETURN_T usage: return_T(Matrix value) : returns Matrix + % 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(67, this, varargin{:}); + else + error('Arguments do not match any overload of function MyTemplateMatrix.return_T'); + end + end + + function varargout = return_Tptr(this, varargin) + % RETURN_TPTR usage: return_Tptr(Matrix value) : returns Matrix + % 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(68, this, varargin{:}); + else + error('Arguments do not match any overload of function MyTemplateMatrix.return_Tptr'); + end + end + + function varargout = return_ptrs(this, varargin) + % RETURN_PTRS usage: return_ptrs(Matrix p1, Matrix p2) : returns pair< Matrix, Matrix > + % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html + if length(varargin) == 2 && isa(varargin{1},'double') && isa(varargin{2},'double') + [ varargout{1} varargout{2} ] = geometry_wrapper(69, this, varargin{:}); + else + error('Arguments do not match any overload of function MyTemplateMatrix.return_ptrs'); + end + end + + function varargout = templatedMethodMatrix(this, varargin) + % TEMPLATEDMETHODMATRIX usage: templatedMethodMatrix(Matrix t) : returns Matrix + % 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(70, this, varargin{:}); + else + error('Arguments do not match any overload of function MyTemplateMatrix.templatedMethod'); + end + end + + function varargout = templatedMethodPoint2(this, varargin) + % TEMPLATEDMETHODPOINT2 usage: templatedMethodPoint2(Point2 t) : returns gtsam::Point2 + % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html + if length(varargin) == 1 && isa(varargin{1},'gtsam.Point2') + varargout{1} = geometry_wrapper(71, this, varargin{:}); + else + error('Arguments do not match any overload of function MyTemplateMatrix.templatedMethod'); + end + end + + function varargout = templatedMethodPoint3(this, varargin) + % TEMPLATEDMETHODPOINT3 usage: templatedMethodPoint3(Point3 t) : returns gtsam::Point3 + % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html + if length(varargin) == 1 && isa(varargin{1},'gtsam.Point3') + varargout{1} = geometry_wrapper(72, this, varargin{:}); + else + error('Arguments do not match any overload of function MyTemplateMatrix.templatedMethod'); + end + end + + function varargout = templatedMethodVector(this, varargin) + % TEMPLATEDMETHODVECTOR usage: templatedMethodVector(Vector t) : returns Vector + % 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') && size(varargin{1},2)==1 + varargout{1} = geometry_wrapper(73, this, varargin{:}); + else + error('Arguments do not match any overload of function MyTemplateMatrix.templatedMethod'); + end + end + + end + + methods(Static = true) + end +end diff --git a/wrap/tests/expected2/geometry_wrapper.cpp b/wrap/tests/expected2/geometry_wrapper.cpp index 04e236426..82926e2ce 100644 --- a/wrap/tests/expected2/geometry_wrapper.cpp +++ b/wrap/tests/expected2/geometry_wrapper.cpp @@ -5,7 +5,7 @@ #include typedef MyTemplate MyTemplatePoint2; -typedef MyTemplate MyTemplatePoint3; +typedef MyTemplate MyTemplateMatrix; typedef MyFactor MyFactorPosePoint2; typedef std::set*> Collector_gtsamPoint2; @@ -18,8 +18,8 @@ typedef std::set*> Collector_MyBase; static Collector_MyBase collector_MyBase; typedef std::set*> Collector_MyTemplatePoint2; static Collector_MyTemplatePoint2 collector_MyTemplatePoint2; -typedef std::set*> Collector_MyTemplatePoint3; -static Collector_MyTemplatePoint3 collector_MyTemplatePoint3; +typedef std::set*> Collector_MyTemplateMatrix; +static Collector_MyTemplateMatrix collector_MyTemplateMatrix; typedef std::set*> Collector_MyFactorPosePoint2; static Collector_MyFactorPosePoint2 collector_MyFactorPosePoint2; @@ -59,10 +59,10 @@ void _deleteAllObjects() collector_MyTemplatePoint2.erase(iter++); anyDeleted = true; } } - { for(Collector_MyTemplatePoint3::iterator iter = collector_MyTemplatePoint3.begin(); - iter != collector_MyTemplatePoint3.end(); ) { + { for(Collector_MyTemplateMatrix::iterator iter = collector_MyTemplateMatrix.begin(); + iter != collector_MyTemplateMatrix.end(); ) { delete *iter; - collector_MyTemplatePoint3.erase(iter++); + collector_MyTemplateMatrix.erase(iter++); anyDeleted = true; } } { for(Collector_MyFactorPosePoint2::iterator iter = collector_MyFactorPosePoint2.begin(); @@ -85,7 +85,7 @@ void _geometry_RTTIRegister() { 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(MyTemplatePoint3).name(), "MyTemplatePoint3")); + types.insert(std::make_pair(typeid(MyTemplateMatrix).name(), "MyTemplateMatrix")); mxArray *registry = mexGetVariable("global", "gtsamwrap_rttiRegistry"); if(!registry) @@ -712,35 +712,35 @@ void MyTemplatePoint2_templatedMethod_58(int nargout, mxArray *out[], int nargin out[0] = wrap< Vector >(obj->templatedMethod(t)); } -void MyTemplatePoint3_collectorInsertAndMakeBase_59(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void MyTemplateMatrix_collectorInsertAndMakeBase_59(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { mexAtExit(&_deleteAllObjects); - typedef boost::shared_ptr Shared; + typedef boost::shared_ptr Shared; Shared *self = *reinterpret_cast (mxGetData(in[0])); - collector_MyTemplatePoint3.insert(self); + 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 MyTemplatePoint3_upcastFromVoid_60(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { +void MyTemplateMatrix_upcastFromVoid_60(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { mexAtExit(&_deleteAllObjects); - typedef boost::shared_ptr Shared; + 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)); + Shared *self = new Shared(boost::static_pointer_cast(*asVoid)); *reinterpret_cast(mxGetData(out[0])) = self; } -void MyTemplatePoint3_constructor_61(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void MyTemplateMatrix_constructor_61(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { mexAtExit(&_deleteAllObjects); - typedef boost::shared_ptr Shared; + typedef boost::shared_ptr Shared; - Shared *self = new Shared(new MyTemplatePoint3()); - collector_MyTemplatePoint3.insert(self); + Shared *self = new Shared(new MyTemplateMatrix()); + collector_MyTemplateMatrix.insert(self); out[0] = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL); *reinterpret_cast (mxGetData(out[0])) = self; @@ -749,129 +749,139 @@ void MyTemplatePoint3_constructor_61(int nargout, mxArray *out[], int nargin, co *reinterpret_cast(mxGetData(out[1])) = new SharedBase(*self); } -void MyTemplatePoint3_deconstructor_62(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void MyTemplateMatrix_deconstructor_62(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { - typedef boost::shared_ptr Shared; - checkArguments("delete_MyTemplatePoint3",nargout,nargin,1); + typedef boost::shared_ptr Shared; + checkArguments("delete_MyTemplateMatrix",nargout,nargin,1); Shared *self = *reinterpret_cast(mxGetData(in[0])); - Collector_MyTemplatePoint3::iterator item; - item = collector_MyTemplatePoint3.find(self); - if(item != collector_MyTemplatePoint3.end()) { + Collector_MyTemplateMatrix::iterator item; + item = collector_MyTemplateMatrix.find(self); + if(item != collector_MyTemplateMatrix.end()) { delete self; - collector_MyTemplatePoint3.erase(item); + collector_MyTemplateMatrix.erase(item); } } -void MyTemplatePoint3_accept_T_63(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void MyTemplateMatrix_accept_T_63(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { - typedef boost::shared_ptr Shared; + typedef boost::shared_ptr Shared; checkArguments("accept_T",nargout,nargin-1,1); - Shared obj = unwrap_shared_ptr(in[0], "ptr_MyTemplatePoint3"); - gtsam::Point3& value = *unwrap_shared_ptr< gtsam::Point3 >(in[1], "ptr_gtsamPoint3"); + Shared obj = unwrap_shared_ptr(in[0], "ptr_MyTemplateMatrix"); + Matrix& value = *unwrap_shared_ptr< Matrix >(in[1], "ptr_Matrix"); obj->accept_T(value); } -void MyTemplatePoint3_accept_Tptr_64(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void MyTemplateMatrix_accept_Tptr_64(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { - typedef boost::shared_ptr Shared; + typedef boost::shared_ptr Shared; checkArguments("accept_Tptr",nargout,nargin-1,1); - Shared obj = unwrap_shared_ptr(in[0], "ptr_MyTemplatePoint3"); - boost::shared_ptr value = unwrap_shared_ptr< gtsam::Point3 >(in[1], "ptr_gtsamPoint3"); + Shared obj = unwrap_shared_ptr(in[0], "ptr_MyTemplateMatrix"); + boost::shared_ptr value = unwrap_shared_ptr< Matrix >(in[1], "ptr_Matrix"); obj->accept_Tptr(value); } -void MyTemplatePoint3_create_MixedPtrs_65(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void MyTemplateMatrix_create_MixedPtrs_65(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { - typedef boost::shared_ptr SharedPoint3; - typedef boost::shared_ptr SharedPoint3; - typedef boost::shared_ptr Shared; + typedef boost::shared_ptr Shared; checkArguments("create_MixedPtrs",nargout,nargin-1,0); - Shared obj = unwrap_shared_ptr(in[0], "ptr_MyTemplatePoint3"); - pair< gtsam::Point3, SharedPoint3 > pairResult = obj->create_MixedPtrs(); - out[0] = wrap_shared_ptr(SharedPoint3(new gtsam::Point3(pairResult.first)),"gtsam.Point3", false); - out[1] = wrap_shared_ptr(pairResult.second,"gtsam.Point3", false); + Shared obj = unwrap_shared_ptr(in[0], "ptr_MyTemplateMatrix"); + pair< Matrix, SharedMatrix > pairResult = obj->create_MixedPtrs(); + out[0] = wrap< Matrix >(pairResult.first); + { + SharedMatrix* ret = new SharedMatrix(pairResult.second); + out[1] = wrap_shared_ptr(ret,"Matrix"); + } } -void MyTemplatePoint3_create_ptrs_66(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void MyTemplateMatrix_create_ptrs_66(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { - typedef boost::shared_ptr SharedPoint3; - typedef boost::shared_ptr SharedPoint3; - typedef boost::shared_ptr Shared; + typedef boost::shared_ptr Shared; checkArguments("create_ptrs",nargout,nargin-1,0); - Shared obj = unwrap_shared_ptr(in[0], "ptr_MyTemplatePoint3"); - pair< SharedPoint3, SharedPoint3 > pairResult = obj->create_ptrs(); - out[0] = wrap_shared_ptr(pairResult.first,"gtsam.Point3", false); - out[1] = wrap_shared_ptr(pairResult.second,"gtsam.Point3", false); + Shared obj = unwrap_shared_ptr(in[0], "ptr_MyTemplateMatrix"); + pair< SharedMatrix, SharedMatrix > pairResult = obj->create_ptrs(); + { + SharedMatrix* ret = new SharedMatrix(pairResult.first); + out[0] = wrap_shared_ptr(ret,"Matrix"); + } + { + SharedMatrix* ret = new SharedMatrix(pairResult.second); + out[1] = wrap_shared_ptr(ret,"Matrix"); + } } -void MyTemplatePoint3_return_T_67(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void MyTemplateMatrix_return_T_67(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { - typedef boost::shared_ptr SharedPoint3; - typedef boost::shared_ptr Shared; + typedef boost::shared_ptr Shared; checkArguments("return_T",nargout,nargin-1,1); - Shared obj = unwrap_shared_ptr(in[0], "ptr_MyTemplatePoint3"); - boost::shared_ptr value = unwrap_shared_ptr< gtsam::Point3 >(in[1], "ptr_gtsamPoint3"); - out[0] = wrap_shared_ptr(SharedPoint3(new gtsam::Point3(obj->return_T(value))),"gtsam.Point3", false); + Shared obj = unwrap_shared_ptr(in[0], "ptr_MyTemplateMatrix"); + boost::shared_ptr value = unwrap_shared_ptr< Matrix >(in[1], "ptr_Matrix"); + out[0] = wrap< Matrix >(obj->return_T(value)); } -void MyTemplatePoint3_return_Tptr_68(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void MyTemplateMatrix_return_Tptr_68(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { - typedef boost::shared_ptr SharedPoint3; - typedef boost::shared_ptr Shared; + typedef boost::shared_ptr Shared; checkArguments("return_Tptr",nargout,nargin-1,1); - Shared obj = unwrap_shared_ptr(in[0], "ptr_MyTemplatePoint3"); - boost::shared_ptr value = unwrap_shared_ptr< gtsam::Point3 >(in[1], "ptr_gtsamPoint3"); - out[0] = wrap_shared_ptr(obj->return_Tptr(value),"gtsam.Point3", false); + Shared obj = unwrap_shared_ptr(in[0], "ptr_MyTemplateMatrix"); + boost::shared_ptr value = unwrap_shared_ptr< Matrix >(in[1], "ptr_Matrix"); + { + SharedMatrix* ret = new SharedMatrix(obj->return_Tptr(value)); + out[0] = wrap_shared_ptr(ret,"Matrix"); + } } -void MyTemplatePoint3_return_ptrs_69(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void MyTemplateMatrix_return_ptrs_69(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { - typedef boost::shared_ptr SharedPoint3; - typedef boost::shared_ptr SharedPoint3; - typedef boost::shared_ptr Shared; + typedef boost::shared_ptr Shared; checkArguments("return_ptrs",nargout,nargin-1,2); - Shared obj = unwrap_shared_ptr(in[0], "ptr_MyTemplatePoint3"); - boost::shared_ptr p1 = unwrap_shared_ptr< gtsam::Point3 >(in[1], "ptr_gtsamPoint3"); - boost::shared_ptr p2 = unwrap_shared_ptr< gtsam::Point3 >(in[2], "ptr_gtsamPoint3"); - pair< SharedPoint3, SharedPoint3 > pairResult = obj->return_ptrs(p1,p2); - out[0] = wrap_shared_ptr(pairResult.first,"gtsam.Point3", false); - out[1] = wrap_shared_ptr(pairResult.second,"gtsam.Point3", false); + Shared obj = unwrap_shared_ptr(in[0], "ptr_MyTemplateMatrix"); + boost::shared_ptr p1 = unwrap_shared_ptr< Matrix >(in[1], "ptr_Matrix"); + boost::shared_ptr p2 = unwrap_shared_ptr< Matrix >(in[2], "ptr_Matrix"); + pair< SharedMatrix, SharedMatrix > pairResult = obj->return_ptrs(p1,p2); + { + SharedMatrix* ret = new SharedMatrix(pairResult.first); + out[0] = wrap_shared_ptr(ret,"Matrix"); + } + { + SharedMatrix* ret = new SharedMatrix(pairResult.second); + out[1] = wrap_shared_ptr(ret,"Matrix"); + } } -void MyTemplatePoint3_templatedMethod_70(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void MyTemplateMatrix_templatedMethod_70(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { - typedef boost::shared_ptr Shared; + typedef boost::shared_ptr Shared; checkArguments("templatedMethodMatrix",nargout,nargin-1,1); - Shared obj = unwrap_shared_ptr(in[0], "ptr_MyTemplatePoint3"); + Shared obj = unwrap_shared_ptr(in[0], "ptr_MyTemplateMatrix"); Matrix& t = *unwrap_shared_ptr< Matrix >(in[1], "ptr_Matrix"); out[0] = wrap< Matrix >(obj->templatedMethod(t)); } -void MyTemplatePoint3_templatedMethod_71(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void MyTemplateMatrix_templatedMethod_71(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr SharedPoint2; - typedef boost::shared_ptr Shared; + typedef boost::shared_ptr Shared; checkArguments("templatedMethodPoint2",nargout,nargin-1,1); - Shared obj = unwrap_shared_ptr(in[0], "ptr_MyTemplatePoint3"); + Shared obj = unwrap_shared_ptr(in[0], "ptr_MyTemplateMatrix"); gtsam::Point2& t = *unwrap_shared_ptr< gtsam::Point2 >(in[1], "ptr_gtsamPoint2"); out[0] = wrap_shared_ptr(SharedPoint2(new gtsam::Point2(obj->templatedMethod(t))),"gtsam.Point2", false); } -void MyTemplatePoint3_templatedMethod_72(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void MyTemplateMatrix_templatedMethod_72(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr SharedPoint3; - typedef boost::shared_ptr Shared; + typedef boost::shared_ptr Shared; checkArguments("templatedMethodPoint3",nargout,nargin-1,1); - Shared obj = unwrap_shared_ptr(in[0], "ptr_MyTemplatePoint3"); + Shared obj = unwrap_shared_ptr(in[0], "ptr_MyTemplateMatrix"); gtsam::Point3& t = *unwrap_shared_ptr< gtsam::Point3 >(in[1], "ptr_gtsamPoint3"); out[0] = wrap_shared_ptr(SharedPoint3(new gtsam::Point3(obj->templatedMethod(t))),"gtsam.Point3", false); } -void MyTemplatePoint3_templatedMethod_73(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void MyTemplateMatrix_templatedMethod_73(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { - typedef boost::shared_ptr Shared; + typedef boost::shared_ptr Shared; checkArguments("templatedMethodVector",nargout,nargin-1,1); - Shared obj = unwrap_shared_ptr(in[0], "ptr_MyTemplatePoint3"); + Shared obj = unwrap_shared_ptr(in[0], "ptr_MyTemplateMatrix"); Vector& t = *unwrap_shared_ptr< Vector >(in[1], "ptr_Vector"); out[0] = wrap< Vector >(obj->templatedMethod(t)); } @@ -1121,49 +1131,49 @@ void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) MyTemplatePoint2_templatedMethod_58(nargout, out, nargin-1, in+1); break; case 59: - MyTemplatePoint3_collectorInsertAndMakeBase_59(nargout, out, nargin-1, in+1); + MyTemplateMatrix_collectorInsertAndMakeBase_59(nargout, out, nargin-1, in+1); break; case 60: - MyTemplatePoint3_upcastFromVoid_60(nargout, out, nargin-1, in+1); + MyTemplateMatrix_upcastFromVoid_60(nargout, out, nargin-1, in+1); break; case 61: - MyTemplatePoint3_constructor_61(nargout, out, nargin-1, in+1); + MyTemplateMatrix_constructor_61(nargout, out, nargin-1, in+1); break; case 62: - MyTemplatePoint3_deconstructor_62(nargout, out, nargin-1, in+1); + MyTemplateMatrix_deconstructor_62(nargout, out, nargin-1, in+1); break; case 63: - MyTemplatePoint3_accept_T_63(nargout, out, nargin-1, in+1); + MyTemplateMatrix_accept_T_63(nargout, out, nargin-1, in+1); break; case 64: - MyTemplatePoint3_accept_Tptr_64(nargout, out, nargin-1, in+1); + MyTemplateMatrix_accept_Tptr_64(nargout, out, nargin-1, in+1); break; case 65: - MyTemplatePoint3_create_MixedPtrs_65(nargout, out, nargin-1, in+1); + MyTemplateMatrix_create_MixedPtrs_65(nargout, out, nargin-1, in+1); break; case 66: - MyTemplatePoint3_create_ptrs_66(nargout, out, nargin-1, in+1); + MyTemplateMatrix_create_ptrs_66(nargout, out, nargin-1, in+1); break; case 67: - MyTemplatePoint3_return_T_67(nargout, out, nargin-1, in+1); + MyTemplateMatrix_return_T_67(nargout, out, nargin-1, in+1); break; case 68: - MyTemplatePoint3_return_Tptr_68(nargout, out, nargin-1, in+1); + MyTemplateMatrix_return_Tptr_68(nargout, out, nargin-1, in+1); break; case 69: - MyTemplatePoint3_return_ptrs_69(nargout, out, nargin-1, in+1); + MyTemplateMatrix_return_ptrs_69(nargout, out, nargin-1, in+1); break; case 70: - MyTemplatePoint3_templatedMethod_70(nargout, out, nargin-1, in+1); + MyTemplateMatrix_templatedMethod_70(nargout, out, nargin-1, in+1); break; case 71: - MyTemplatePoint3_templatedMethod_71(nargout, out, nargin-1, in+1); + MyTemplateMatrix_templatedMethod_71(nargout, out, nargin-1, in+1); break; case 72: - MyTemplatePoint3_templatedMethod_72(nargout, out, nargin-1, in+1); + MyTemplateMatrix_templatedMethod_72(nargout, out, nargin-1, in+1); break; case 73: - MyTemplatePoint3_templatedMethod_73(nargout, out, nargin-1, in+1); + MyTemplateMatrix_templatedMethod_73(nargout, out, nargin-1, in+1); break; case 74: MyFactorPosePoint2_collectorInsertAndMakeBase_74(nargout, out, nargin-1, in+1); diff --git a/wrap/tests/geometry.h b/wrap/tests/geometry.h index 0646ff456..78e2a1dff 100644 --- a/wrap/tests/geometry.h +++ b/wrap/tests/geometry.h @@ -101,7 +101,7 @@ virtual class MyBase { }; // A templated class -template +template virtual class MyTemplate : MyBase { MyTemplate(); From 08c9243acb50b7151e0e1c73e56b2d78d9e78428 Mon Sep 17 00:00:00 2001 From: dellaert Date: Mon, 1 Dec 2014 14:47:09 +0100 Subject: [PATCH 077/126] Fixed tests --- .../tests/expected-python/geometry_python.cpp | 26 +- wrap/tests/expected/+gtsam/Point2.m | 19 +- wrap/tests/expected/+gtsam/Point3.m | 16 +- wrap/tests/expected/MyBase.m | 6 +- wrap/tests/expected/MyFactorPosePoint2.m | 6 +- .../MyTemplateMatrix.m} | 100 ++-- wrap/tests/expected/MyTemplatePoint2.m | 48 +- wrap/tests/expected/MyTemplatePoint3.m | 156 ------ wrap/tests/expected/Test.m | 52 +- wrap/tests/expected/aGlobalFunction.m | 2 +- wrap/tests/expected/geometry_wrapper.cpp | 475 +++++++++--------- .../tests/expected/overloadedGlobalFunction.m | 4 +- wrap/tests/testWrap.cpp | 2 +- 13 files changed, 397 insertions(+), 515 deletions(-) rename wrap/tests/{expected2/MyTemplatePoint3.m => expected/MyTemplateMatrix.m} (64%) delete mode 100644 wrap/tests/expected/MyTemplatePoint3.m diff --git a/wrap/tests/expected-python/geometry_python.cpp b/wrap/tests/expected-python/geometry_python.cpp index ca8698397..609b67476 100644 --- a/wrap/tests/expected-python/geometry_python.cpp +++ b/wrap/tests/expected-python/geometry_python.cpp @@ -64,19 +64,19 @@ class_("MyTemplatePoint2") .def("templatedMethod", &MyTemplatePoint2::templatedMethod); ; -class_("MyTemplatePoint3") - .def("MyTemplatePoint3", &MyTemplatePoint3::MyTemplatePoint3); - .def("accept_T", &MyTemplatePoint3::accept_T); - .def("accept_Tptr", &MyTemplatePoint3::accept_Tptr); - .def("create_MixedPtrs", &MyTemplatePoint3::create_MixedPtrs); - .def("create_ptrs", &MyTemplatePoint3::create_ptrs); - .def("return_T", &MyTemplatePoint3::return_T); - .def("return_Tptr", &MyTemplatePoint3::return_Tptr); - .def("return_ptrs", &MyTemplatePoint3::return_ptrs); - .def("templatedMethod", &MyTemplatePoint3::templatedMethod); - .def("templatedMethod", &MyTemplatePoint3::templatedMethod); - .def("templatedMethod", &MyTemplatePoint3::templatedMethod); - .def("templatedMethod", &MyTemplatePoint3::templatedMethod); +class_("MyTemplateMatrix") + .def("MyTemplateMatrix", &MyTemplateMatrix::MyTemplateMatrix); + .def("accept_T", &MyTemplateMatrix::accept_T); + .def("accept_Tptr", &MyTemplateMatrix::accept_Tptr); + .def("create_MixedPtrs", &MyTemplateMatrix::create_MixedPtrs); + .def("create_ptrs", &MyTemplateMatrix::create_ptrs); + .def("return_T", &MyTemplateMatrix::return_T); + .def("return_Tptr", &MyTemplateMatrix::return_Tptr); + .def("return_ptrs", &MyTemplateMatrix::return_ptrs); + .def("templatedMethod", &MyTemplateMatrix::templatedMethod); + .def("templatedMethod", &MyTemplateMatrix::templatedMethod); + .def("templatedMethod", &MyTemplateMatrix::templatedMethod); + .def("templatedMethod", &MyTemplateMatrix::templatedMethod); ; class_("MyFactorPosePoint2") diff --git a/wrap/tests/expected/+gtsam/Point2.m b/wrap/tests/expected/+gtsam/Point2.m index 308b35d9a..05ca8b9a0 100644 --- a/wrap/tests/expected/+gtsam/Point2.m +++ b/wrap/tests/expected/+gtsam/Point2.m @@ -9,6 +9,7 @@ %argChar(char a) : returns void %argUChar(unsigned char a) : returns void %dim() : returns int +%eigenArguments(Vector v, Matrix m) : returns void %returnChar() : returns char %vectorConfusion() : returns VectorNotEigen %x() : returns double @@ -59,28 +60,38 @@ classdef Point2 < handle varargout{1} = geometry_wrapper(6, this, varargin{:}); end + function varargout = eigenArguments(this, varargin) + % EIGENARGUMENTS usage: eigenArguments(Vector v, Matrix m) : returns void + % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html + if length(varargin) == 2 && isa(varargin{1},'double') && size(varargin{1},2)==1 && isa(varargin{2},'double') + geometry_wrapper(7, this, varargin{:}); + else + error('Arguments do not match any overload of function gtsam.Point2.eigenArguments'); + end + end + function varargout = returnChar(this, varargin) % RETURNCHAR usage: returnChar() : returns char % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html - varargout{1} = geometry_wrapper(7, this, varargin{:}); + varargout{1} = geometry_wrapper(8, this, varargin{:}); end function varargout = vectorConfusion(this, varargin) % VECTORCONFUSION usage: vectorConfusion() : returns VectorNotEigen % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html - varargout{1} = geometry_wrapper(8, this, varargin{:}); + varargout{1} = geometry_wrapper(9, this, varargin{:}); end function varargout = x(this, varargin) % X usage: x() : returns double % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html - varargout{1} = geometry_wrapper(9, this, varargin{:}); + varargout{1} = geometry_wrapper(10, this, varargin{:}); end function varargout = y(this, varargin) % Y usage: y() : returns double % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html - varargout{1} = geometry_wrapper(10, this, varargin{:}); + varargout{1} = geometry_wrapper(11, this, varargin{:}); end end diff --git a/wrap/tests/expected/+gtsam/Point3.m b/wrap/tests/expected/+gtsam/Point3.m index a9a28c14c..7b8a973c0 100644 --- a/wrap/tests/expected/+gtsam/Point3.m +++ b/wrap/tests/expected/+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(11, my_ptr); + geometry_wrapper(12, my_ptr); elseif nargin == 3 && isa(varargin{1},'double') && isa(varargin{2},'double') && isa(varargin{3},'double') - my_ptr = geometry_wrapper(12, varargin{1}, varargin{2}, varargin{3}); + my_ptr = geometry_wrapper(13, 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(13, obj.ptr_gtsamPoint3); + geometry_wrapper(14, obj.ptr_gtsamPoint3); end function display(obj), obj.print(''); end @@ -43,14 +43,14 @@ classdef Point3 < handle function varargout = norm(this, varargin) % NORM usage: norm() : returns double % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html - varargout{1} = geometry_wrapper(14, this, varargin{:}); + varargout{1} = geometry_wrapper(15, this, varargin{:}); end function varargout = string_serialize(this, varargin) % STRING_SERIALIZE usage: string_serialize() : returns string % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html if length(varargin) == 0 - varargout{1} = geometry_wrapper(15, this, varargin{:}); + varargout{1} = geometry_wrapper(16, this, varargin{:}); else error('Arguments do not match any overload of function gtsam.Point3.string_serialize'); end @@ -66,20 +66,20 @@ classdef Point3 < handle function varargout = StaticFunctionRet(varargin) % STATICFUNCTIONRET usage: StaticFunctionRet(double z) : returns gtsam::Point3 % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html - varargout{1} = geometry_wrapper(16, varargin{:}); + varargout{1} = geometry_wrapper(17, varargin{:}); end function varargout = StaticFunction(varargin) % STATICFUNCTION usage: staticFunction() : returns double % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html - varargout{1} = geometry_wrapper(17, varargin{:}); + varargout{1} = geometry_wrapper(18, varargin{:}); end function varargout = string_deserialize(varargin) % STRING_DESERIALIZE usage: string_deserialize() : returns gtsam.Point3 % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html if length(varargin) == 1 - varargout{1} = geometry_wrapper(18, varargin{:}); + varargout{1} = geometry_wrapper(19, varargin{:}); else error('Arguments do not match any overload of function gtsam.Point3.string_deserialize'); end diff --git a/wrap/tests/expected/MyBase.m b/wrap/tests/expected/MyBase.m index 34d3cb4c0..ff8179220 100644 --- a/wrap/tests/expected/MyBase.m +++ b/wrap/tests/expected/MyBase.m @@ -11,9 +11,9 @@ classdef MyBase < handle if nargin == 2 my_ptr = varargin{2}; else - my_ptr = geometry_wrapper(43, varargin{2}); + my_ptr = geometry_wrapper(44, varargin{2}); end - geometry_wrapper(42, my_ptr); + geometry_wrapper(43, 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(44, obj.ptr_MyBase); + geometry_wrapper(45, obj.ptr_MyBase); end function display(obj), obj.print(''); end diff --git a/wrap/tests/expected/MyFactorPosePoint2.m b/wrap/tests/expected/MyFactorPosePoint2.m index 496a2c1e8..2dff98803 100644 --- a/wrap/tests/expected/MyFactorPosePoint2.m +++ b/wrap/tests/expected/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(75, my_ptr); + geometry_wrapper(76, 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(76, varargin{1}, varargin{2}, varargin{3}, varargin{4}); + my_ptr = geometry_wrapper(77, 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(77, obj.ptr_MyFactorPosePoint2); + geometry_wrapper(78, obj.ptr_MyFactorPosePoint2); end function display(obj), obj.print(''); end diff --git a/wrap/tests/expected2/MyTemplatePoint3.m b/wrap/tests/expected/MyTemplateMatrix.m similarity index 64% rename from wrap/tests/expected2/MyTemplatePoint3.m rename to wrap/tests/expected/MyTemplateMatrix.m index 45fe34a0a..b17bbdbe7 100644 --- a/wrap/tests/expected2/MyTemplatePoint3.m +++ b/wrap/tests/expected/MyTemplateMatrix.m @@ -1,46 +1,46 @@ -%class MyTemplatePoint3, see Doxygen page for details +%class MyTemplateMatrix, see Doxygen page for details %at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html % %-------Constructors------- -%MyTemplatePoint3() +%MyTemplateMatrix() % %-------Methods------- -%accept_T(Point3 value) : returns void -%accept_Tptr(Point3 value) : returns void -%create_MixedPtrs() : returns pair< gtsam::Point3, gtsam::Point3 > -%create_ptrs() : returns pair< gtsam::Point3, gtsam::Point3 > -%return_T(Point3 value) : returns gtsam::Point3 -%return_Tptr(Point3 value) : returns gtsam::Point3 -%return_ptrs(Point3 p1, Point3 p2) : returns pair< gtsam::Point3, gtsam::Point3 > +%accept_T(Matrix value) : returns void +%accept_Tptr(Matrix value) : returns void +%create_MixedPtrs() : returns pair< Matrix, Matrix > +%create_ptrs() : returns pair< Matrix, Matrix > +%return_T(Matrix value) : returns Matrix +%return_Tptr(Matrix value) : returns Matrix +%return_ptrs(Matrix p1, Matrix p2) : returns pair< Matrix, Matrix > %templatedMethodMatrix(Matrix t) : returns Matrix %templatedMethodPoint2(Point2 t) : returns gtsam::Point2 %templatedMethodPoint3(Point3 t) : returns gtsam::Point3 %templatedMethodVector(Vector t) : returns Vector % -classdef MyTemplatePoint3 < MyBase +classdef MyTemplateMatrix < MyBase properties - ptr_MyTemplatePoint3 = 0 + ptr_MyTemplateMatrix = 0 end methods - function obj = MyTemplatePoint3(varargin) + function obj = MyTemplateMatrix(varargin) if (nargin == 2 || (nargin == 3 && strcmp(varargin{3}, 'void'))) && isa(varargin{1}, 'uint64') && varargin{1} == uint64(5139824614673773682) if nargin == 2 my_ptr = varargin{2}; else - my_ptr = geometry_wrapper(60, varargin{2}); + my_ptr = geometry_wrapper(62, varargin{2}); end - base_ptr = geometry_wrapper(59, my_ptr); + base_ptr = geometry_wrapper(61, my_ptr); elseif nargin == 0 - [ my_ptr, base_ptr ] = geometry_wrapper(61); + [ my_ptr, base_ptr ] = geometry_wrapper(63); else - error('Arguments do not match any overload of MyTemplatePoint3 constructor'); + error('Arguments do not match any overload of MyTemplateMatrix constructor'); end obj = obj@MyBase(uint64(5139824614673773682), base_ptr); - obj.ptr_MyTemplatePoint3 = my_ptr; + obj.ptr_MyTemplateMatrix = my_ptr; end function delete(obj) - geometry_wrapper(62, obj.ptr_MyTemplatePoint3); + geometry_wrapper(64, obj.ptr_MyTemplateMatrix); end function display(obj), obj.print(''); end @@ -48,64 +48,64 @@ classdef MyTemplatePoint3 < MyBase function disp(obj), obj.display; end %DISP Calls print on the object function varargout = accept_T(this, varargin) - % ACCEPT_T usage: accept_T(Point3 value) : returns void + % ACCEPT_T usage: accept_T(Matrix value) : returns void % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html - if length(varargin) == 1 && isa(varargin{1},'gtsam.Point3') - geometry_wrapper(63, this, varargin{:}); + if length(varargin) == 1 && isa(varargin{1},'double') + geometry_wrapper(65, this, varargin{:}); else - error('Arguments do not match any overload of function MyTemplatePoint3.accept_T'); + error('Arguments do not match any overload of function MyTemplateMatrix.accept_T'); end end function varargout = accept_Tptr(this, varargin) - % ACCEPT_TPTR usage: accept_Tptr(Point3 value) : returns void + % ACCEPT_TPTR usage: accept_Tptr(Matrix value) : returns void % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html - if length(varargin) == 1 && isa(varargin{1},'gtsam.Point3') - geometry_wrapper(64, this, varargin{:}); + if length(varargin) == 1 && isa(varargin{1},'double') + geometry_wrapper(66, this, varargin{:}); else - error('Arguments do not match any overload of function MyTemplatePoint3.accept_Tptr'); + error('Arguments do not match any overload of function MyTemplateMatrix.accept_Tptr'); end end function varargout = create_MixedPtrs(this, varargin) - % CREATE_MIXEDPTRS usage: create_MixedPtrs() : returns pair< gtsam::Point3, gtsam::Point3 > + % CREATE_MIXEDPTRS usage: create_MixedPtrs() : returns pair< Matrix, Matrix > % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html - [ varargout{1} varargout{2} ] = geometry_wrapper(65, this, varargin{:}); + [ varargout{1} varargout{2} ] = geometry_wrapper(67, this, varargin{:}); end function varargout = create_ptrs(this, varargin) - % CREATE_PTRS usage: create_ptrs() : returns pair< gtsam::Point3, gtsam::Point3 > + % CREATE_PTRS usage: create_ptrs() : returns pair< Matrix, Matrix > % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html - [ varargout{1} varargout{2} ] = geometry_wrapper(66, this, varargin{:}); + [ varargout{1} varargout{2} ] = geometry_wrapper(68, this, varargin{:}); end function varargout = return_T(this, varargin) - % RETURN_T usage: return_T(Point3 value) : returns gtsam::Point3 + % RETURN_T usage: return_T(Matrix value) : returns Matrix % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html - if length(varargin) == 1 && isa(varargin{1},'gtsam.Point3') - varargout{1} = geometry_wrapper(67, this, varargin{:}); + if length(varargin) == 1 && isa(varargin{1},'double') + varargout{1} = geometry_wrapper(69, this, varargin{:}); else - error('Arguments do not match any overload of function MyTemplatePoint3.return_T'); + error('Arguments do not match any overload of function MyTemplateMatrix.return_T'); end end function varargout = return_Tptr(this, varargin) - % RETURN_TPTR usage: return_Tptr(Point3 value) : returns gtsam::Point3 + % RETURN_TPTR usage: return_Tptr(Matrix value) : returns Matrix % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html - if length(varargin) == 1 && isa(varargin{1},'gtsam.Point3') - varargout{1} = geometry_wrapper(68, this, varargin{:}); + if length(varargin) == 1 && isa(varargin{1},'double') + varargout{1} = geometry_wrapper(70, this, varargin{:}); else - error('Arguments do not match any overload of function MyTemplatePoint3.return_Tptr'); + error('Arguments do not match any overload of function MyTemplateMatrix.return_Tptr'); end end function varargout = return_ptrs(this, varargin) - % RETURN_PTRS usage: return_ptrs(Point3 p1, Point3 p2) : returns pair< gtsam::Point3, gtsam::Point3 > + % RETURN_PTRS usage: return_ptrs(Matrix p1, Matrix p2) : returns pair< Matrix, Matrix > % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html - if length(varargin) == 2 && isa(varargin{1},'gtsam.Point3') && isa(varargin{2},'gtsam.Point3') - [ varargout{1} varargout{2} ] = geometry_wrapper(69, this, varargin{:}); + if length(varargin) == 2 && isa(varargin{1},'double') && isa(varargin{2},'double') + [ varargout{1} varargout{2} ] = geometry_wrapper(71, this, varargin{:}); else - error('Arguments do not match any overload of function MyTemplatePoint3.return_ptrs'); + error('Arguments do not match any overload of function MyTemplateMatrix.return_ptrs'); end end @@ -113,9 +113,9 @@ classdef MyTemplatePoint3 < MyBase % TEMPLATEDMETHODMATRIX usage: templatedMethodMatrix(Matrix t) : returns Matrix % 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(70, this, varargin{:}); + varargout{1} = geometry_wrapper(72, this, varargin{:}); else - error('Arguments do not match any overload of function MyTemplatePoint3.templatedMethod'); + error('Arguments do not match any overload of function MyTemplateMatrix.templatedMethod'); end end @@ -123,9 +123,9 @@ classdef MyTemplatePoint3 < MyBase % TEMPLATEDMETHODPOINT2 usage: templatedMethodPoint2(Point2 t) : returns gtsam::Point2 % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html if length(varargin) == 1 && isa(varargin{1},'gtsam.Point2') - varargout{1} = geometry_wrapper(71, this, varargin{:}); + varargout{1} = geometry_wrapper(73, this, varargin{:}); else - error('Arguments do not match any overload of function MyTemplatePoint3.templatedMethod'); + error('Arguments do not match any overload of function MyTemplateMatrix.templatedMethod'); end end @@ -133,9 +133,9 @@ classdef MyTemplatePoint3 < MyBase % TEMPLATEDMETHODPOINT3 usage: templatedMethodPoint3(Point3 t) : returns gtsam::Point3 % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html if length(varargin) == 1 && isa(varargin{1},'gtsam.Point3') - varargout{1} = geometry_wrapper(72, this, varargin{:}); + varargout{1} = geometry_wrapper(74, this, varargin{:}); else - error('Arguments do not match any overload of function MyTemplatePoint3.templatedMethod'); + error('Arguments do not match any overload of function MyTemplateMatrix.templatedMethod'); end end @@ -143,9 +143,9 @@ classdef MyTemplatePoint3 < MyBase % TEMPLATEDMETHODVECTOR usage: templatedMethodVector(Vector t) : returns Vector % 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') && size(varargin{1},2)==1 - varargout{1} = geometry_wrapper(73, this, varargin{:}); + varargout{1} = geometry_wrapper(75, this, varargin{:}); else - error('Arguments do not match any overload of function MyTemplatePoint3.templatedMethod'); + error('Arguments do not match any overload of function MyTemplateMatrix.templatedMethod'); end end diff --git a/wrap/tests/expected/MyTemplatePoint2.m b/wrap/tests/expected/MyTemplatePoint2.m index e6adb3d2c..d908bd365 100644 --- a/wrap/tests/expected/MyTemplatePoint2.m +++ b/wrap/tests/expected/MyTemplatePoint2.m @@ -12,10 +12,10 @@ %return_T(Point2 value) : returns gtsam::Point2 %return_Tptr(Point2 value) : returns gtsam::Point2 %return_ptrs(Point2 p1, Point2 p2) : returns pair< gtsam::Point2, gtsam::Point2 > -%templatedMethodMatrix(Matrix t) : returns void -%templatedMethodPoint2(Point2 t) : returns void -%templatedMethodPoint3(Point3 t) : returns void -%templatedMethodVector(Vector t) : returns void +%templatedMethodMatrix(Matrix t) : returns Matrix +%templatedMethodPoint2(Point2 t) : returns gtsam::Point2 +%templatedMethodPoint3(Point3 t) : returns gtsam::Point3 +%templatedMethodVector(Vector t) : returns Vector % classdef MyTemplatePoint2 < MyBase properties @@ -27,11 +27,11 @@ classdef MyTemplatePoint2 < MyBase if nargin == 2 my_ptr = varargin{2}; else - my_ptr = geometry_wrapper(46, varargin{2}); + my_ptr = geometry_wrapper(47, varargin{2}); end - base_ptr = geometry_wrapper(45, my_ptr); + base_ptr = geometry_wrapper(46, my_ptr); elseif nargin == 0 - [ my_ptr, base_ptr ] = geometry_wrapper(47); + [ my_ptr, base_ptr ] = geometry_wrapper(48); else error('Arguments do not match any overload of MyTemplatePoint2 constructor'); end @@ -40,7 +40,7 @@ classdef MyTemplatePoint2 < MyBase end function delete(obj) - geometry_wrapper(48, obj.ptr_MyTemplatePoint2); + geometry_wrapper(49, obj.ptr_MyTemplatePoint2); end function display(obj), obj.print(''); end @@ -51,7 +51,7 @@ classdef MyTemplatePoint2 < MyBase % ACCEPT_T usage: accept_T(Point2 value) : returns void % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html if length(varargin) == 1 && isa(varargin{1},'gtsam.Point2') - geometry_wrapper(49, this, varargin{:}); + geometry_wrapper(50, this, varargin{:}); else error('Arguments do not match any overload of function MyTemplatePoint2.accept_T'); end @@ -61,7 +61,7 @@ classdef MyTemplatePoint2 < MyBase % ACCEPT_TPTR usage: accept_Tptr(Point2 value) : returns void % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html if length(varargin) == 1 && isa(varargin{1},'gtsam.Point2') - geometry_wrapper(50, this, varargin{:}); + geometry_wrapper(51, this, varargin{:}); else error('Arguments do not match any overload of function MyTemplatePoint2.accept_Tptr'); end @@ -70,20 +70,20 @@ classdef MyTemplatePoint2 < MyBase function varargout = create_MixedPtrs(this, varargin) % CREATE_MIXEDPTRS usage: create_MixedPtrs() : returns pair< gtsam::Point2, gtsam::Point2 > % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html - [ varargout{1} varargout{2} ] = geometry_wrapper(51, this, varargin{:}); + [ varargout{1} varargout{2} ] = geometry_wrapper(52, this, varargin{:}); end function varargout = create_ptrs(this, varargin) % CREATE_PTRS usage: create_ptrs() : returns pair< gtsam::Point2, gtsam::Point2 > % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html - [ varargout{1} varargout{2} ] = geometry_wrapper(52, this, varargin{:}); + [ varargout{1} varargout{2} ] = geometry_wrapper(53, this, varargin{:}); end function varargout = return_T(this, varargin) % RETURN_T usage: return_T(Point2 value) : returns gtsam::Point2 % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html if length(varargin) == 1 && isa(varargin{1},'gtsam.Point2') - varargout{1} = geometry_wrapper(53, this, varargin{:}); + varargout{1} = geometry_wrapper(54, this, varargin{:}); else error('Arguments do not match any overload of function MyTemplatePoint2.return_T'); end @@ -93,7 +93,7 @@ classdef MyTemplatePoint2 < MyBase % RETURN_TPTR usage: return_Tptr(Point2 value) : returns gtsam::Point2 % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html if length(varargin) == 1 && isa(varargin{1},'gtsam.Point2') - varargout{1} = geometry_wrapper(54, this, varargin{:}); + varargout{1} = geometry_wrapper(55, this, varargin{:}); else error('Arguments do not match any overload of function MyTemplatePoint2.return_Tptr'); end @@ -103,47 +103,47 @@ classdef MyTemplatePoint2 < MyBase % RETURN_PTRS usage: return_ptrs(Point2 p1, Point2 p2) : returns pair< gtsam::Point2, gtsam::Point2 > % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html if length(varargin) == 2 && isa(varargin{1},'gtsam.Point2') && isa(varargin{2},'gtsam.Point2') - [ varargout{1} varargout{2} ] = geometry_wrapper(55, this, varargin{:}); + [ varargout{1} varargout{2} ] = geometry_wrapper(56, this, varargin{:}); else error('Arguments do not match any overload of function MyTemplatePoint2.return_ptrs'); end end function varargout = templatedMethodMatrix(this, varargin) - % TEMPLATEDMETHODMATRIX usage: templatedMethodMatrix(Matrix t) : returns void + % TEMPLATEDMETHODMATRIX usage: templatedMethodMatrix(Matrix t) : returns Matrix % 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') - geometry_wrapper(56, this, varargin{:}); + varargout{1} = geometry_wrapper(57, this, varargin{:}); else error('Arguments do not match any overload of function MyTemplatePoint2.templatedMethod'); end end function varargout = templatedMethodPoint2(this, varargin) - % TEMPLATEDMETHODPOINT2 usage: templatedMethodPoint2(Point2 t) : returns void + % TEMPLATEDMETHODPOINT2 usage: templatedMethodPoint2(Point2 t) : returns gtsam::Point2 % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html if length(varargin) == 1 && isa(varargin{1},'gtsam.Point2') - geometry_wrapper(57, this, varargin{:}); + varargout{1} = geometry_wrapper(58, this, varargin{:}); else error('Arguments do not match any overload of function MyTemplatePoint2.templatedMethod'); end end function varargout = templatedMethodPoint3(this, varargin) - % TEMPLATEDMETHODPOINT3 usage: templatedMethodPoint3(Point3 t) : returns void + % TEMPLATEDMETHODPOINT3 usage: templatedMethodPoint3(Point3 t) : returns gtsam::Point3 % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html if length(varargin) == 1 && isa(varargin{1},'gtsam.Point3') - geometry_wrapper(58, this, varargin{:}); + varargout{1} = geometry_wrapper(59, this, varargin{:}); else error('Arguments do not match any overload of function MyTemplatePoint2.templatedMethod'); end end function varargout = templatedMethodVector(this, varargin) - % TEMPLATEDMETHODVECTOR usage: templatedMethodVector(Vector t) : returns void + % TEMPLATEDMETHODVECTOR usage: templatedMethodVector(Vector t) : returns Vector % 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') - geometry_wrapper(59, this, varargin{:}); + if length(varargin) == 1 && isa(varargin{1},'double') && size(varargin{1},2)==1 + varargout{1} = geometry_wrapper(60, this, varargin{:}); else error('Arguments do not match any overload of function MyTemplatePoint2.templatedMethod'); end diff --git a/wrap/tests/expected/MyTemplatePoint3.m b/wrap/tests/expected/MyTemplatePoint3.m deleted file mode 100644 index 9819b5ee1..000000000 --- a/wrap/tests/expected/MyTemplatePoint3.m +++ /dev/null @@ -1,156 +0,0 @@ -%class MyTemplatePoint3, see Doxygen page for details -%at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html -% -%-------Constructors------- -%MyTemplatePoint3() -% -%-------Methods------- -%accept_T(Point3 value) : returns void -%accept_Tptr(Point3 value) : returns void -%create_MixedPtrs() : returns pair< gtsam::Point3, gtsam::Point3 > -%create_ptrs() : returns pair< gtsam::Point3, gtsam::Point3 > -%return_T(Point3 value) : returns gtsam::Point3 -%return_Tptr(Point3 value) : returns gtsam::Point3 -%return_ptrs(Point3 p1, Point3 p2) : returns pair< gtsam::Point3, gtsam::Point3 > -%templatedMethodMatrix(Matrix t) : returns void -%templatedMethodPoint2(Point2 t) : returns void -%templatedMethodPoint3(Point3 t) : returns void -%templatedMethodVector(Vector t) : returns void -% -classdef MyTemplatePoint3 < MyBase - properties - ptr_MyTemplatePoint3 = 0 - end - methods - function obj = MyTemplatePoint3(varargin) - if (nargin == 2 || (nargin == 3 && strcmp(varargin{3}, 'void'))) && isa(varargin{1}, 'uint64') && varargin{1} == uint64(5139824614673773682) - if nargin == 2 - my_ptr = varargin{2}; - else - my_ptr = geometry_wrapper(61, varargin{2}); - end - base_ptr = geometry_wrapper(60, my_ptr); - elseif nargin == 0 - [ my_ptr, base_ptr ] = geometry_wrapper(62); - else - error('Arguments do not match any overload of MyTemplatePoint3 constructor'); - end - obj = obj@MyBase(uint64(5139824614673773682), base_ptr); - obj.ptr_MyTemplatePoint3 = my_ptr; - end - - function delete(obj) - geometry_wrapper(63, obj.ptr_MyTemplatePoint3); - 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 = accept_T(this, varargin) - % ACCEPT_T usage: accept_T(Point3 value) : returns void - % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html - if length(varargin) == 1 && isa(varargin{1},'gtsam.Point3') - geometry_wrapper(64, this, varargin{:}); - else - error('Arguments do not match any overload of function MyTemplatePoint3.accept_T'); - end - end - - function varargout = accept_Tptr(this, varargin) - % ACCEPT_TPTR usage: accept_Tptr(Point3 value) : returns void - % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html - if length(varargin) == 1 && isa(varargin{1},'gtsam.Point3') - geometry_wrapper(65, this, varargin{:}); - else - error('Arguments do not match any overload of function MyTemplatePoint3.accept_Tptr'); - end - end - - function varargout = create_MixedPtrs(this, varargin) - % CREATE_MIXEDPTRS usage: create_MixedPtrs() : returns pair< gtsam::Point3, gtsam::Point3 > - % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html - [ varargout{1} varargout{2} ] = geometry_wrapper(66, this, varargin{:}); - end - - function varargout = create_ptrs(this, varargin) - % CREATE_PTRS usage: create_ptrs() : returns pair< gtsam::Point3, gtsam::Point3 > - % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html - [ varargout{1} varargout{2} ] = geometry_wrapper(67, this, varargin{:}); - end - - function varargout = return_T(this, varargin) - % RETURN_T usage: return_T(Point3 value) : returns gtsam::Point3 - % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html - if length(varargin) == 1 && isa(varargin{1},'gtsam.Point3') - varargout{1} = geometry_wrapper(68, this, varargin{:}); - else - error('Arguments do not match any overload of function MyTemplatePoint3.return_T'); - end - end - - function varargout = return_Tptr(this, varargin) - % RETURN_TPTR usage: return_Tptr(Point3 value) : returns gtsam::Point3 - % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html - if length(varargin) == 1 && isa(varargin{1},'gtsam.Point3') - varargout{1} = geometry_wrapper(69, this, varargin{:}); - else - error('Arguments do not match any overload of function MyTemplatePoint3.return_Tptr'); - end - end - - function varargout = return_ptrs(this, varargin) - % RETURN_PTRS usage: return_ptrs(Point3 p1, Point3 p2) : returns pair< gtsam::Point3, gtsam::Point3 > - % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html - if length(varargin) == 2 && isa(varargin{1},'gtsam.Point3') && isa(varargin{2},'gtsam.Point3') - [ varargout{1} varargout{2} ] = geometry_wrapper(70, this, varargin{:}); - else - error('Arguments do not match any overload of function MyTemplatePoint3.return_ptrs'); - end - end - - function varargout = templatedMethodMatrix(this, varargin) - % TEMPLATEDMETHODMATRIX usage: templatedMethodMatrix(Matrix t) : returns void - % 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') - geometry_wrapper(71, this, varargin{:}); - else - error('Arguments do not match any overload of function MyTemplatePoint3.templatedMethod'); - end - end - - function varargout = templatedMethodPoint2(this, varargin) - % TEMPLATEDMETHODPOINT2 usage: templatedMethodPoint2(Point2 t) : returns void - % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html - if length(varargin) == 1 && isa(varargin{1},'gtsam.Point2') - geometry_wrapper(72, this, varargin{:}); - else - error('Arguments do not match any overload of function MyTemplatePoint3.templatedMethod'); - end - end - - function varargout = templatedMethodPoint3(this, varargin) - % TEMPLATEDMETHODPOINT3 usage: templatedMethodPoint3(Point3 t) : returns void - % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html - if length(varargin) == 1 && isa(varargin{1},'gtsam.Point3') - geometry_wrapper(73, this, varargin{:}); - else - error('Arguments do not match any overload of function MyTemplatePoint3.templatedMethod'); - end - end - - function varargout = templatedMethodVector(this, varargin) - % TEMPLATEDMETHODVECTOR usage: templatedMethodVector(Vector t) : returns void - % 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') - geometry_wrapper(74, this, varargin{:}); - else - error('Arguments do not match any overload of function MyTemplatePoint3.templatedMethod'); - end - end - - end - - methods(Static = true) - end -end diff --git a/wrap/tests/expected/Test.m b/wrap/tests/expected/Test.m index 352312789..44b8211b9 100644 --- a/wrap/tests/expected/Test.m +++ b/wrap/tests/expected/Test.m @@ -34,11 +34,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(19, my_ptr); + geometry_wrapper(20, my_ptr); elseif nargin == 0 - my_ptr = geometry_wrapper(20); + my_ptr = geometry_wrapper(21); elseif nargin == 2 && isa(varargin{1},'double') && isa(varargin{2},'double') - my_ptr = geometry_wrapper(21, varargin{1}, varargin{2}); + my_ptr = geometry_wrapper(22, varargin{1}, varargin{2}); else error('Arguments do not match any overload of Test constructor'); end @@ -46,7 +46,7 @@ classdef Test < handle end function delete(obj) - geometry_wrapper(22, obj.ptr_Test); + geometry_wrapper(23, obj.ptr_Test); end function display(obj), obj.print(''); end @@ -57,7 +57,7 @@ classdef Test < handle % ARG_EIGENCONSTREF usage: arg_EigenConstRef(Matrix value) : returns void % 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') - geometry_wrapper(23, this, varargin{:}); + geometry_wrapper(24, this, varargin{:}); else error('Arguments do not match any overload of function Test.arg_EigenConstRef'); end @@ -66,32 +66,32 @@ classdef Test < handle function varargout = create_MixedPtrs(this, varargin) % CREATE_MIXEDPTRS usage: create_MixedPtrs() : returns pair< Test, Test > % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html - [ varargout{1} varargout{2} ] = geometry_wrapper(24, this, varargin{:}); + [ varargout{1} varargout{2} ] = geometry_wrapper(25, this, varargin{:}); end function varargout = create_ptrs(this, varargin) % CREATE_PTRS usage: create_ptrs() : returns pair< Test, Test > % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html - [ varargout{1} varargout{2} ] = geometry_wrapper(25, this, varargin{:}); + [ varargout{1} varargout{2} ] = geometry_wrapper(26, this, varargin{:}); end function varargout = print(this, varargin) % PRINT usage: print() : returns void % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html - geometry_wrapper(26, this, varargin{:}); + geometry_wrapper(27, this, varargin{:}); end function varargout = return_Point2Ptr(this, varargin) % RETURN_POINT2PTR usage: return_Point2Ptr(bool value) : returns gtsam::Point2 % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html - varargout{1} = geometry_wrapper(27, this, varargin{:}); + varargout{1} = geometry_wrapper(28, this, varargin{:}); end function varargout = return_Test(this, varargin) % RETURN_TEST usage: return_Test(Test value) : returns Test % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html if length(varargin) == 1 && isa(varargin{1},'Test') - varargout{1} = geometry_wrapper(28, this, varargin{:}); + varargout{1} = geometry_wrapper(29, this, varargin{:}); else error('Arguments do not match any overload of function Test.return_Test'); end @@ -101,7 +101,7 @@ classdef Test < handle % RETURN_TESTPTR usage: return_TestPtr(Test value) : returns Test % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html if length(varargin) == 1 && isa(varargin{1},'Test') - varargout{1} = geometry_wrapper(29, this, varargin{:}); + varargout{1} = geometry_wrapper(30, this, varargin{:}); else error('Arguments do not match any overload of function Test.return_TestPtr'); end @@ -110,20 +110,20 @@ classdef Test < handle function varargout = return_bool(this, varargin) % RETURN_BOOL usage: return_bool(bool value) : returns bool % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html - varargout{1} = geometry_wrapper(30, this, varargin{:}); + varargout{1} = geometry_wrapper(31, this, varargin{:}); end function varargout = return_double(this, varargin) % RETURN_DOUBLE usage: return_double(double value) : returns double % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html - varargout{1} = geometry_wrapper(31, this, varargin{:}); + varargout{1} = geometry_wrapper(32, this, varargin{:}); end function varargout = return_field(this, varargin) % RETURN_FIELD usage: return_field(Test t) : returns bool % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html if length(varargin) == 1 && isa(varargin{1},'Test') - varargout{1} = geometry_wrapper(32, this, varargin{:}); + varargout{1} = geometry_wrapper(33, this, varargin{:}); else error('Arguments do not match any overload of function Test.return_field'); end @@ -132,14 +132,14 @@ classdef Test < handle function varargout = return_int(this, varargin) % RETURN_INT usage: return_int(int value) : returns int % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html - varargout{1} = geometry_wrapper(33, this, varargin{:}); + varargout{1} = geometry_wrapper(34, this, varargin{:}); end function varargout = return_matrix1(this, varargin) % RETURN_MATRIX1 usage: return_matrix1(Matrix value) : returns Matrix % 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(34, this, varargin{:}); + varargout{1} = geometry_wrapper(35, this, varargin{:}); else error('Arguments do not match any overload of function Test.return_matrix1'); end @@ -149,7 +149,7 @@ classdef Test < handle % RETURN_MATRIX2 usage: return_matrix2(Matrix value) : returns Matrix % 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(35, this, varargin{:}); + varargout{1} = geometry_wrapper(36, this, varargin{:}); else error('Arguments do not match any overload of function Test.return_matrix2'); end @@ -158,8 +158,8 @@ classdef Test < handle function varargout = return_pair(this, varargin) % RETURN_PAIR usage: return_pair(Vector v, Matrix A) : returns pair< Vector, Matrix > % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html - if length(varargin) == 2 && isa(varargin{1},'double') && isa(varargin{2},'double') - [ varargout{1} varargout{2} ] = geometry_wrapper(36, this, varargin{:}); + 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{:}); else error('Arguments do not match any overload of function Test.return_pair'); end @@ -169,7 +169,7 @@ classdef Test < handle % RETURN_PTRS usage: return_ptrs(Test p1, Test p2) : returns pair< Test, Test > % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html if length(varargin) == 2 && isa(varargin{1},'Test') && isa(varargin{2},'Test') - [ varargout{1} varargout{2} ] = geometry_wrapper(37, this, varargin{:}); + [ varargout{1} varargout{2} ] = geometry_wrapper(38, this, varargin{:}); else error('Arguments do not match any overload of function Test.return_ptrs'); end @@ -178,14 +178,14 @@ classdef Test < handle function varargout = return_size_t(this, varargin) % RETURN_SIZE_T usage: return_size_t(size_t value) : returns size_t % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html - varargout{1} = geometry_wrapper(38, this, varargin{:}); + varargout{1} = geometry_wrapper(39, this, varargin{:}); end function varargout = return_string(this, varargin) % RETURN_STRING usage: return_string(string value) : returns string % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html if length(varargin) == 1 && isa(varargin{1},'char') - varargout{1} = geometry_wrapper(39, this, varargin{:}); + varargout{1} = geometry_wrapper(40, this, varargin{:}); else error('Arguments do not match any overload of function Test.return_string'); end @@ -194,8 +194,8 @@ classdef Test < handle function varargout = return_vector1(this, varargin) % RETURN_VECTOR1 usage: return_vector1(Vector value) : returns Vector % 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(40, this, varargin{:}); + if length(varargin) == 1 && isa(varargin{1},'double') && size(varargin{1},2)==1 + varargout{1} = geometry_wrapper(41, this, varargin{:}); else error('Arguments do not match any overload of function Test.return_vector1'); end @@ -204,8 +204,8 @@ classdef Test < handle function varargout = return_vector2(this, varargin) % RETURN_VECTOR2 usage: return_vector2(Vector value) : returns Vector % 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(41, this, varargin{:}); + if length(varargin) == 1 && isa(varargin{1},'double') && size(varargin{1},2)==1 + varargout{1} = geometry_wrapper(42, this, varargin{:}); else error('Arguments do not match any overload of function Test.return_vector2'); end diff --git a/wrap/tests/expected/aGlobalFunction.m b/wrap/tests/expected/aGlobalFunction.m index 2e725c658..df970c759 100644 --- a/wrap/tests/expected/aGlobalFunction.m +++ b/wrap/tests/expected/aGlobalFunction.m @@ -1,6 +1,6 @@ function varargout = aGlobalFunction(varargin) if length(varargin) == 0 - varargout{1} = geometry_wrapper(78, varargin{:}); + varargout{1} = geometry_wrapper(79, varargin{:}); else error('Arguments do not match any overload of function aGlobalFunction'); end diff --git a/wrap/tests/expected/geometry_wrapper.cpp b/wrap/tests/expected/geometry_wrapper.cpp index 52eb42efd..527600b47 100644 --- a/wrap/tests/expected/geometry_wrapper.cpp +++ b/wrap/tests/expected/geometry_wrapper.cpp @@ -9,7 +9,7 @@ #include typedef MyTemplate MyTemplatePoint2; -typedef MyTemplate MyTemplatePoint3; +typedef MyTemplate MyTemplateMatrix; typedef MyFactor MyFactorPosePoint2; BOOST_CLASS_EXPORT_GUID(gtsam::Point2, "gtsamPoint2"); @@ -25,8 +25,8 @@ typedef std::set*> Collector_MyBase; static Collector_MyBase collector_MyBase; typedef std::set*> Collector_MyTemplatePoint2; static Collector_MyTemplatePoint2 collector_MyTemplatePoint2; -typedef std::set*> Collector_MyTemplatePoint3; -static Collector_MyTemplatePoint3 collector_MyTemplatePoint3; +typedef std::set*> Collector_MyTemplateMatrix; +static Collector_MyTemplateMatrix collector_MyTemplateMatrix; typedef std::set*> Collector_MyFactorPosePoint2; static Collector_MyFactorPosePoint2 collector_MyFactorPosePoint2; @@ -66,10 +66,10 @@ void _deleteAllObjects() collector_MyTemplatePoint2.erase(iter++); anyDeleted = true; } } - { for(Collector_MyTemplatePoint3::iterator iter = collector_MyTemplatePoint3.begin(); - iter != collector_MyTemplatePoint3.end(); ) { + { for(Collector_MyTemplateMatrix::iterator iter = collector_MyTemplateMatrix.begin(); + iter != collector_MyTemplateMatrix.end(); ) { delete *iter; - collector_MyTemplatePoint3.erase(iter++); + collector_MyTemplateMatrix.erase(iter++); anyDeleted = true; } } { for(Collector_MyFactorPosePoint2::iterator iter = collector_MyFactorPosePoint2.begin(); @@ -92,7 +92,7 @@ void _geometry_RTTIRegister() { 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(MyTemplatePoint3).name(), "MyTemplatePoint3")); + types.insert(std::make_pair(typeid(MyTemplateMatrix).name(), "MyTemplateMatrix")); mxArray *registry = mexGetVariable("global", "gtsamwrap_rttiRegistry"); if(!registry) @@ -188,7 +188,17 @@ void gtsamPoint2_dim_6(int nargout, mxArray *out[], int nargin, const mxArray *i out[0] = wrap< int >(obj->dim()); } -void gtsamPoint2_returnChar_7(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void gtsamPoint2_eigenArguments_7(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + typedef boost::shared_ptr Shared; + checkArguments("eigenArguments",nargout,nargin-1,2); + Shared 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_8(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr Shared; checkArguments("returnChar",nargout,nargin-1,0); @@ -196,7 +206,7 @@ void gtsamPoint2_returnChar_7(int nargout, mxArray *out[], int nargin, const mxA out[0] = wrap< char >(obj->returnChar()); } -void gtsamPoint2_vectorConfusion_8(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void gtsamPoint2_vectorConfusion_9(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr SharedVectorNotEigen; typedef boost::shared_ptr Shared; @@ -205,7 +215,7 @@ void gtsamPoint2_vectorConfusion_8(int nargout, mxArray *out[], int nargin, cons out[0] = wrap_shared_ptr(SharedVectorNotEigen(new VectorNotEigen(obj->vectorConfusion())),"VectorNotEigen", false); } -void gtsamPoint2_x_9(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void gtsamPoint2_x_10(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr Shared; checkArguments("x",nargout,nargin-1,0); @@ -213,7 +223,7 @@ void gtsamPoint2_x_9(int nargout, mxArray *out[], int nargin, const mxArray *in[ out[0] = wrap< double >(obj->x()); } -void gtsamPoint2_y_10(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void gtsamPoint2_y_11(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr Shared; checkArguments("y",nargout,nargin-1,0); @@ -221,7 +231,7 @@ void gtsamPoint2_y_10(int nargout, mxArray *out[], int nargin, const mxArray *in out[0] = wrap< double >(obj->y()); } -void gtsamPoint3_collectorInsertAndMakeBase_11(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void gtsamPoint3_collectorInsertAndMakeBase_12(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { mexAtExit(&_deleteAllObjects); typedef boost::shared_ptr Shared; @@ -230,7 +240,7 @@ void gtsamPoint3_collectorInsertAndMakeBase_11(int nargout, mxArray *out[], int collector_gtsamPoint3.insert(self); } -void gtsamPoint3_constructor_12(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void gtsamPoint3_constructor_13(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { mexAtExit(&_deleteAllObjects); typedef boost::shared_ptr Shared; @@ -244,7 +254,7 @@ void gtsamPoint3_constructor_12(int nargout, mxArray *out[], int nargin, const m *reinterpret_cast (mxGetData(out[0])) = self; } -void gtsamPoint3_deconstructor_13(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void gtsamPoint3_deconstructor_14(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr Shared; checkArguments("delete_gtsamPoint3",nargout,nargin,1); @@ -257,7 +267,7 @@ void gtsamPoint3_deconstructor_13(int nargout, mxArray *out[], int nargin, const } } -void gtsamPoint3_norm_14(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void gtsamPoint3_norm_15(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr Shared; checkArguments("norm",nargout,nargin-1,0); @@ -265,7 +275,7 @@ void gtsamPoint3_norm_14(int nargout, mxArray *out[], int nargin, const mxArray out[0] = wrap< double >(obj->norm()); } -void gtsamPoint3_string_serialize_15(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void gtsamPoint3_string_serialize_16(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr Shared; checkArguments("string_serialize",nargout,nargin-1,0); @@ -275,7 +285,7 @@ void gtsamPoint3_string_serialize_15(int nargout, mxArray *out[], int nargin, co out_archive << *obj; out[0] = wrap< string >(out_archive_stream.str()); } -void gtsamPoint3_StaticFunctionRet_16(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void gtsamPoint3_StaticFunctionRet_17(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr SharedPoint3; typedef boost::shared_ptr Shared; @@ -284,14 +294,14 @@ void gtsamPoint3_StaticFunctionRet_16(int nargout, mxArray *out[], int nargin, c out[0] = wrap_shared_ptr(SharedPoint3(new gtsam::Point3(gtsam::Point3::StaticFunctionRet(z))),"gtsam.Point3", false); } -void gtsamPoint3_staticFunction_17(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void gtsamPoint3_staticFunction_18(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr Shared; checkArguments("gtsamPoint3.staticFunction",nargout,nargin,0); out[0] = wrap< double >(gtsam::Point3::staticFunction()); } -void gtsamPoint3_string_deserialize_18(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void gtsamPoint3_string_deserialize_19(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr Shared; checkArguments("gtsamPoint3.string_deserialize",nargout,nargin,1); @@ -302,7 +312,7 @@ void gtsamPoint3_string_deserialize_18(int nargout, mxArray *out[], int nargin, in_archive >> *output; out[0] = wrap_shared_ptr(output,"gtsam.Point3", false); } -void Test_collectorInsertAndMakeBase_19(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void Test_collectorInsertAndMakeBase_20(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { mexAtExit(&_deleteAllObjects); typedef boost::shared_ptr Shared; @@ -311,7 +321,7 @@ void Test_collectorInsertAndMakeBase_19(int nargout, mxArray *out[], int nargin, collector_Test.insert(self); } -void Test_constructor_20(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void Test_constructor_21(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { mexAtExit(&_deleteAllObjects); typedef boost::shared_ptr Shared; @@ -322,7 +332,7 @@ void Test_constructor_20(int nargout, mxArray *out[], int nargin, const mxArray *reinterpret_cast (mxGetData(out[0])) = self; } -void Test_constructor_21(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void Test_constructor_22(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { mexAtExit(&_deleteAllObjects); typedef boost::shared_ptr Shared; @@ -335,7 +345,7 @@ void Test_constructor_21(int nargout, mxArray *out[], int nargin, const mxArray *reinterpret_cast (mxGetData(out[0])) = self; } -void Test_deconstructor_22(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void Test_deconstructor_23(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr Shared; checkArguments("delete_Test",nargout,nargin,1); @@ -348,7 +358,7 @@ void Test_deconstructor_22(int nargout, mxArray *out[], int nargin, const mxArra } } -void Test_arg_EigenConstRef_23(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void Test_arg_EigenConstRef_24(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr Shared; checkArguments("arg_EigenConstRef",nargout,nargin-1,1); @@ -357,7 +367,7 @@ void Test_arg_EigenConstRef_23(int nargout, mxArray *out[], int nargin, const mx obj->arg_EigenConstRef(value); } -void Test_create_MixedPtrs_24(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void Test_create_MixedPtrs_25(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr SharedTest; typedef boost::shared_ptr SharedTest; @@ -369,7 +379,7 @@ void Test_create_MixedPtrs_24(int nargout, mxArray *out[], int nargin, const mxA out[1] = wrap_shared_ptr(pairResult.second,"Test", false); } -void Test_create_ptrs_25(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void Test_create_ptrs_26(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr SharedTest; typedef boost::shared_ptr SharedTest; @@ -381,7 +391,7 @@ void Test_create_ptrs_25(int nargout, mxArray *out[], int nargin, const mxArray out[1] = wrap_shared_ptr(pairResult.second,"Test", false); } -void Test_print_26(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void Test_print_27(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr Shared; checkArguments("print",nargout,nargin-1,0); @@ -389,7 +399,7 @@ void Test_print_26(int nargout, mxArray *out[], int nargin, const mxArray *in[]) obj->print(); } -void Test_return_Point2Ptr_27(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void Test_return_Point2Ptr_28(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr SharedPoint2; typedef boost::shared_ptr Shared; @@ -399,7 +409,7 @@ void Test_return_Point2Ptr_27(int nargout, mxArray *out[], int nargin, const mxA out[0] = wrap_shared_ptr(obj->return_Point2Ptr(value),"gtsam.Point2", false); } -void Test_return_Test_28(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void Test_return_Test_29(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr SharedTest; typedef boost::shared_ptr Shared; @@ -409,7 +419,7 @@ void Test_return_Test_28(int nargout, mxArray *out[], int nargin, const mxArray out[0] = wrap_shared_ptr(SharedTest(new Test(obj->return_Test(value))),"Test", false); } -void Test_return_TestPtr_29(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void Test_return_TestPtr_30(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr SharedTest; typedef boost::shared_ptr Shared; @@ -419,7 +429,7 @@ void Test_return_TestPtr_29(int nargout, mxArray *out[], int nargin, const mxArr out[0] = wrap_shared_ptr(obj->return_TestPtr(value),"Test", false); } -void Test_return_bool_30(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void Test_return_bool_31(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr Shared; checkArguments("return_bool",nargout,nargin-1,1); @@ -428,7 +438,7 @@ void Test_return_bool_30(int nargout, mxArray *out[], int nargin, const mxArray out[0] = wrap< bool >(obj->return_bool(value)); } -void Test_return_double_31(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void Test_return_double_32(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr Shared; checkArguments("return_double",nargout,nargin-1,1); @@ -437,7 +447,7 @@ void Test_return_double_31(int nargout, mxArray *out[], int nargin, const mxArra out[0] = wrap< double >(obj->return_double(value)); } -void Test_return_field_32(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void Test_return_field_33(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr Shared; checkArguments("return_field",nargout,nargin-1,1); @@ -446,7 +456,7 @@ void Test_return_field_32(int nargout, mxArray *out[], int nargin, const mxArray out[0] = wrap< bool >(obj->return_field(t)); } -void Test_return_int_33(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void Test_return_int_34(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr Shared; checkArguments("return_int",nargout,nargin-1,1); @@ -455,7 +465,7 @@ void Test_return_int_33(int nargout, mxArray *out[], int nargin, const mxArray * out[0] = wrap< int >(obj->return_int(value)); } -void Test_return_matrix1_34(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void Test_return_matrix1_35(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr Shared; checkArguments("return_matrix1",nargout,nargin-1,1); @@ -464,7 +474,7 @@ void Test_return_matrix1_34(int nargout, mxArray *out[], int nargin, const mxArr out[0] = wrap< Matrix >(obj->return_matrix1(value)); } -void Test_return_matrix2_35(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void Test_return_matrix2_36(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr Shared; checkArguments("return_matrix2",nargout,nargin-1,1); @@ -473,7 +483,7 @@ void Test_return_matrix2_35(int nargout, mxArray *out[], int nargin, const mxArr out[0] = wrap< Matrix >(obj->return_matrix2(value)); } -void Test_return_pair_36(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void Test_return_pair_37(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr Shared; checkArguments("return_pair",nargout,nargin-1,2); @@ -485,7 +495,7 @@ void Test_return_pair_36(int nargout, mxArray *out[], int nargin, const mxArray out[1] = wrap< Matrix >(pairResult.second); } -void Test_return_ptrs_37(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void Test_return_ptrs_38(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr SharedTest; typedef boost::shared_ptr SharedTest; @@ -499,7 +509,7 @@ void Test_return_ptrs_37(int nargout, mxArray *out[], int nargin, const mxArray out[1] = wrap_shared_ptr(pairResult.second,"Test", false); } -void Test_return_size_t_38(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void Test_return_size_t_39(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr Shared; checkArguments("return_size_t",nargout,nargin-1,1); @@ -508,7 +518,7 @@ void Test_return_size_t_38(int nargout, mxArray *out[], int nargin, const mxArra out[0] = wrap< size_t >(obj->return_size_t(value)); } -void Test_return_string_39(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void Test_return_string_40(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr Shared; checkArguments("return_string",nargout,nargin-1,1); @@ -517,7 +527,7 @@ void Test_return_string_39(int nargout, mxArray *out[], int nargin, const mxArra out[0] = wrap< string >(obj->return_string(value)); } -void Test_return_vector1_40(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void Test_return_vector1_41(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr Shared; checkArguments("return_vector1",nargout,nargin-1,1); @@ -526,7 +536,7 @@ void Test_return_vector1_40(int nargout, mxArray *out[], int nargin, const mxArr out[0] = wrap< Vector >(obj->return_vector1(value)); } -void Test_return_vector2_41(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void Test_return_vector2_42(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr Shared; checkArguments("return_vector2",nargout,nargin-1,1); @@ -535,7 +545,7 @@ void Test_return_vector2_41(int nargout, mxArray *out[], int nargin, const mxArr out[0] = wrap< Vector >(obj->return_vector2(value)); } -void MyBase_collectorInsertAndMakeBase_42(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void MyBase_collectorInsertAndMakeBase_43(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { mexAtExit(&_deleteAllObjects); typedef boost::shared_ptr Shared; @@ -544,7 +554,7 @@ void MyBase_collectorInsertAndMakeBase_42(int nargout, mxArray *out[], int nargi collector_MyBase.insert(self); } -void MyBase_upcastFromVoid_43(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { +void MyBase_upcastFromVoid_44(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])); @@ -553,7 +563,7 @@ void MyBase_upcastFromVoid_43(int nargout, mxArray *out[], int nargin, const mxA *reinterpret_cast(mxGetData(out[0])) = self; } -void MyBase_deconstructor_44(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void MyBase_deconstructor_45(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr Shared; checkArguments("delete_MyBase",nargout,nargin,1); @@ -566,7 +576,7 @@ void MyBase_deconstructor_44(int nargout, mxArray *out[], int nargin, const mxAr } } -void MyTemplatePoint2_collectorInsertAndMakeBase_45(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void MyTemplatePoint2_collectorInsertAndMakeBase_46(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { mexAtExit(&_deleteAllObjects); typedef boost::shared_ptr Shared; @@ -579,7 +589,7 @@ void MyTemplatePoint2_collectorInsertAndMakeBase_45(int nargout, mxArray *out[], *reinterpret_cast(mxGetData(out[0])) = new SharedBase(*self); } -void MyTemplatePoint2_upcastFromVoid_46(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { +void MyTemplatePoint2_upcastFromVoid_47(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])); @@ -588,7 +598,7 @@ void MyTemplatePoint2_upcastFromVoid_46(int nargout, mxArray *out[], int nargin, *reinterpret_cast(mxGetData(out[0])) = self; } -void MyTemplatePoint2_constructor_47(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void MyTemplatePoint2_constructor_48(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { mexAtExit(&_deleteAllObjects); typedef boost::shared_ptr Shared; @@ -603,7 +613,7 @@ void MyTemplatePoint2_constructor_47(int nargout, mxArray *out[], int nargin, co *reinterpret_cast(mxGetData(out[1])) = new SharedBase(*self); } -void MyTemplatePoint2_deconstructor_48(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void MyTemplatePoint2_deconstructor_49(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr Shared; checkArguments("delete_MyTemplatePoint2",nargout,nargin,1); @@ -616,7 +626,7 @@ void MyTemplatePoint2_deconstructor_48(int nargout, mxArray *out[], int nargin, } } -void MyTemplatePoint2_accept_T_49(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void MyTemplatePoint2_accept_T_50(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr Shared; checkArguments("accept_T",nargout,nargin-1,1); @@ -625,7 +635,7 @@ void MyTemplatePoint2_accept_T_49(int nargout, mxArray *out[], int nargin, const obj->accept_T(value); } -void MyTemplatePoint2_accept_Tptr_50(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void MyTemplatePoint2_accept_Tptr_51(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr Shared; checkArguments("accept_Tptr",nargout,nargin-1,1); @@ -634,7 +644,7 @@ void MyTemplatePoint2_accept_Tptr_50(int nargout, mxArray *out[], int nargin, co obj->accept_Tptr(value); } -void MyTemplatePoint2_create_MixedPtrs_51(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void MyTemplatePoint2_create_MixedPtrs_52(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr SharedPoint2; typedef boost::shared_ptr SharedPoint2; @@ -646,7 +656,7 @@ void MyTemplatePoint2_create_MixedPtrs_51(int nargout, mxArray *out[], int nargi out[1] = wrap_shared_ptr(pairResult.second,"gtsam.Point2", false); } -void MyTemplatePoint2_create_ptrs_52(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void MyTemplatePoint2_create_ptrs_53(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr SharedPoint2; typedef boost::shared_ptr SharedPoint2; @@ -658,7 +668,7 @@ void MyTemplatePoint2_create_ptrs_52(int nargout, mxArray *out[], int nargin, co out[1] = wrap_shared_ptr(pairResult.second,"gtsam.Point2", false); } -void MyTemplatePoint2_return_T_53(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void MyTemplatePoint2_return_T_54(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr SharedPoint2; typedef boost::shared_ptr Shared; @@ -668,7 +678,7 @@ void MyTemplatePoint2_return_T_53(int nargout, mxArray *out[], int nargin, const out[0] = wrap_shared_ptr(SharedPoint2(new gtsam::Point2(obj->return_T(value))),"gtsam.Point2", false); } -void MyTemplatePoint2_return_Tptr_54(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void MyTemplatePoint2_return_Tptr_55(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr SharedPoint2; typedef boost::shared_ptr Shared; @@ -678,7 +688,7 @@ void MyTemplatePoint2_return_Tptr_54(int nargout, mxArray *out[], int nargin, co out[0] = wrap_shared_ptr(obj->return_Tptr(value),"gtsam.Point2", false); } -void MyTemplatePoint2_return_ptrs_55(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void MyTemplatePoint2_return_ptrs_56(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr SharedPoint2; typedef boost::shared_ptr SharedPoint2; @@ -692,71 +702,73 @@ void MyTemplatePoint2_return_ptrs_55(int nargout, mxArray *out[], int nargin, co out[1] = wrap_shared_ptr(pairResult.second,"gtsam.Point2", false); } -void MyTemplatePoint2_templatedMethod_56(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void MyTemplatePoint2_templatedMethod_57(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr Shared; checkArguments("templatedMethodMatrix",nargout,nargin-1,1); Shared obj = unwrap_shared_ptr(in[0], "ptr_MyTemplatePoint2"); Matrix& t = *unwrap_shared_ptr< Matrix >(in[1], "ptr_Matrix"); - obj->templatedMethod(t); -} - -void MyTemplatePoint2_templatedMethod_57(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - typedef boost::shared_ptr Shared; - checkArguments("templatedMethodPoint2",nargout,nargin-1,1); - Shared obj = unwrap_shared_ptr(in[0], "ptr_MyTemplatePoint2"); - gtsam::Point2& t = *unwrap_shared_ptr< gtsam::Point2 >(in[1], "ptr_gtsamPoint2"); - obj->templatedMethod(t); + out[0] = wrap< Matrix >(obj->templatedMethod(t)); } void MyTemplatePoint2_templatedMethod_58(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { + typedef boost::shared_ptr SharedPoint2; + typedef boost::shared_ptr Shared; + checkArguments("templatedMethodPoint2",nargout,nargin-1,1); + Shared obj = unwrap_shared_ptr(in[0], "ptr_MyTemplatePoint2"); + gtsam::Point2& t = *unwrap_shared_ptr< gtsam::Point2 >(in[1], "ptr_gtsamPoint2"); + out[0] = wrap_shared_ptr(SharedPoint2(new gtsam::Point2(obj->templatedMethod(t))),"gtsam.Point2", false); +} + +void MyTemplatePoint2_templatedMethod_59(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + typedef boost::shared_ptr SharedPoint3; typedef boost::shared_ptr Shared; checkArguments("templatedMethodPoint3",nargout,nargin-1,1); Shared obj = unwrap_shared_ptr(in[0], "ptr_MyTemplatePoint2"); gtsam::Point3& t = *unwrap_shared_ptr< gtsam::Point3 >(in[1], "ptr_gtsamPoint3"); - obj->templatedMethod(t); + out[0] = wrap_shared_ptr(SharedPoint3(new gtsam::Point3(obj->templatedMethod(t))),"gtsam.Point3", false); } -void MyTemplatePoint2_templatedMethod_59(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void MyTemplatePoint2_templatedMethod_60(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr Shared; checkArguments("templatedMethodVector",nargout,nargin-1,1); Shared obj = unwrap_shared_ptr(in[0], "ptr_MyTemplatePoint2"); Vector& t = *unwrap_shared_ptr< Vector >(in[1], "ptr_Vector"); - obj->templatedMethod(t); + out[0] = wrap< Vector >(obj->templatedMethod(t)); } -void MyTemplatePoint3_collectorInsertAndMakeBase_60(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void MyTemplateMatrix_collectorInsertAndMakeBase_61(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { mexAtExit(&_deleteAllObjects); - typedef boost::shared_ptr Shared; + typedef boost::shared_ptr Shared; Shared *self = *reinterpret_cast (mxGetData(in[0])); - collector_MyTemplatePoint3.insert(self); + 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 MyTemplatePoint3_upcastFromVoid_61(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { +void MyTemplateMatrix_upcastFromVoid_62(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { mexAtExit(&_deleteAllObjects); - typedef boost::shared_ptr Shared; + 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)); + Shared *self = new Shared(boost::static_pointer_cast(*asVoid)); *reinterpret_cast(mxGetData(out[0])) = self; } -void MyTemplatePoint3_constructor_62(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void MyTemplateMatrix_constructor_63(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { mexAtExit(&_deleteAllObjects); - typedef boost::shared_ptr Shared; + typedef boost::shared_ptr Shared; - Shared *self = new Shared(new MyTemplatePoint3()); - collector_MyTemplatePoint3.insert(self); + Shared *self = new Shared(new MyTemplateMatrix()); + collector_MyTemplateMatrix.insert(self); out[0] = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL); *reinterpret_cast (mxGetData(out[0])) = self; @@ -765,132 +777,144 @@ void MyTemplatePoint3_constructor_62(int nargout, mxArray *out[], int nargin, co *reinterpret_cast(mxGetData(out[1])) = new SharedBase(*self); } -void MyTemplatePoint3_deconstructor_63(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void MyTemplateMatrix_deconstructor_64(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { - typedef boost::shared_ptr Shared; - checkArguments("delete_MyTemplatePoint3",nargout,nargin,1); + typedef boost::shared_ptr Shared; + checkArguments("delete_MyTemplateMatrix",nargout,nargin,1); Shared *self = *reinterpret_cast(mxGetData(in[0])); - Collector_MyTemplatePoint3::iterator item; - item = collector_MyTemplatePoint3.find(self); - if(item != collector_MyTemplatePoint3.end()) { + Collector_MyTemplateMatrix::iterator item; + item = collector_MyTemplateMatrix.find(self); + if(item != collector_MyTemplateMatrix.end()) { delete self; - collector_MyTemplatePoint3.erase(item); + collector_MyTemplateMatrix.erase(item); } } -void MyTemplatePoint3_accept_T_64(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void MyTemplateMatrix_accept_T_65(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { - typedef boost::shared_ptr Shared; + typedef boost::shared_ptr Shared; checkArguments("accept_T",nargout,nargin-1,1); - Shared obj = unwrap_shared_ptr(in[0], "ptr_MyTemplatePoint3"); - gtsam::Point3& value = *unwrap_shared_ptr< gtsam::Point3 >(in[1], "ptr_gtsamPoint3"); + Shared obj = unwrap_shared_ptr(in[0], "ptr_MyTemplateMatrix"); + Matrix& value = *unwrap_shared_ptr< Matrix >(in[1], "ptr_Matrix"); obj->accept_T(value); } -void MyTemplatePoint3_accept_Tptr_65(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void MyTemplateMatrix_accept_Tptr_66(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { - typedef boost::shared_ptr Shared; + typedef boost::shared_ptr Shared; checkArguments("accept_Tptr",nargout,nargin-1,1); - Shared obj = unwrap_shared_ptr(in[0], "ptr_MyTemplatePoint3"); - boost::shared_ptr value = unwrap_shared_ptr< gtsam::Point3 >(in[1], "ptr_gtsamPoint3"); + Shared obj = unwrap_shared_ptr(in[0], "ptr_MyTemplateMatrix"); + boost::shared_ptr value = unwrap_shared_ptr< Matrix >(in[1], "ptr_Matrix"); obj->accept_Tptr(value); } -void MyTemplatePoint3_create_MixedPtrs_66(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void MyTemplateMatrix_create_MixedPtrs_67(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { - typedef boost::shared_ptr SharedPoint3; - typedef boost::shared_ptr SharedPoint3; - typedef boost::shared_ptr Shared; + typedef boost::shared_ptr Shared; checkArguments("create_MixedPtrs",nargout,nargin-1,0); - Shared obj = unwrap_shared_ptr(in[0], "ptr_MyTemplatePoint3"); - pair< gtsam::Point3, SharedPoint3 > pairResult = obj->create_MixedPtrs(); - out[0] = wrap_shared_ptr(SharedPoint3(new gtsam::Point3(pairResult.first)),"gtsam.Point3", false); - out[1] = wrap_shared_ptr(pairResult.second,"gtsam.Point3", false); + Shared obj = unwrap_shared_ptr(in[0], "ptr_MyTemplateMatrix"); + pair< Matrix, SharedMatrix > pairResult = obj->create_MixedPtrs(); + out[0] = wrap< Matrix >(pairResult.first); + { + SharedMatrix* ret = new SharedMatrix(pairResult.second); + out[1] = wrap_shared_ptr(ret,"Matrix"); + } } -void MyTemplatePoint3_create_ptrs_67(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void MyTemplateMatrix_create_ptrs_68(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { - typedef boost::shared_ptr SharedPoint3; - typedef boost::shared_ptr SharedPoint3; - typedef boost::shared_ptr Shared; + typedef boost::shared_ptr Shared; checkArguments("create_ptrs",nargout,nargin-1,0); - Shared obj = unwrap_shared_ptr(in[0], "ptr_MyTemplatePoint3"); - pair< SharedPoint3, SharedPoint3 > pairResult = obj->create_ptrs(); - out[0] = wrap_shared_ptr(pairResult.first,"gtsam.Point3", false); - out[1] = wrap_shared_ptr(pairResult.second,"gtsam.Point3", false); + Shared obj = unwrap_shared_ptr(in[0], "ptr_MyTemplateMatrix"); + pair< SharedMatrix, SharedMatrix > pairResult = obj->create_ptrs(); + { + SharedMatrix* ret = new SharedMatrix(pairResult.first); + out[0] = wrap_shared_ptr(ret,"Matrix"); + } + { + SharedMatrix* ret = new SharedMatrix(pairResult.second); + out[1] = wrap_shared_ptr(ret,"Matrix"); + } } -void MyTemplatePoint3_return_T_68(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void MyTemplateMatrix_return_T_69(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { - typedef boost::shared_ptr SharedPoint3; - typedef boost::shared_ptr Shared; + typedef boost::shared_ptr Shared; checkArguments("return_T",nargout,nargin-1,1); - Shared obj = unwrap_shared_ptr(in[0], "ptr_MyTemplatePoint3"); - boost::shared_ptr value = unwrap_shared_ptr< gtsam::Point3 >(in[1], "ptr_gtsamPoint3"); - out[0] = wrap_shared_ptr(SharedPoint3(new gtsam::Point3(obj->return_T(value))),"gtsam.Point3", false); + Shared obj = unwrap_shared_ptr(in[0], "ptr_MyTemplateMatrix"); + boost::shared_ptr value = unwrap_shared_ptr< Matrix >(in[1], "ptr_Matrix"); + out[0] = wrap< Matrix >(obj->return_T(value)); } -void MyTemplatePoint3_return_Tptr_69(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void MyTemplateMatrix_return_Tptr_70(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { - typedef boost::shared_ptr SharedPoint3; - typedef boost::shared_ptr Shared; + typedef boost::shared_ptr Shared; checkArguments("return_Tptr",nargout,nargin-1,1); - Shared obj = unwrap_shared_ptr(in[0], "ptr_MyTemplatePoint3"); - boost::shared_ptr value = unwrap_shared_ptr< gtsam::Point3 >(in[1], "ptr_gtsamPoint3"); - out[0] = wrap_shared_ptr(obj->return_Tptr(value),"gtsam.Point3", false); + Shared obj = unwrap_shared_ptr(in[0], "ptr_MyTemplateMatrix"); + boost::shared_ptr value = unwrap_shared_ptr< Matrix >(in[1], "ptr_Matrix"); + { + SharedMatrix* ret = new SharedMatrix(obj->return_Tptr(value)); + out[0] = wrap_shared_ptr(ret,"Matrix"); + } } -void MyTemplatePoint3_return_ptrs_70(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void MyTemplateMatrix_return_ptrs_71(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { - typedef boost::shared_ptr SharedPoint3; - typedef boost::shared_ptr SharedPoint3; - typedef boost::shared_ptr Shared; + typedef boost::shared_ptr Shared; checkArguments("return_ptrs",nargout,nargin-1,2); - Shared obj = unwrap_shared_ptr(in[0], "ptr_MyTemplatePoint3"); - boost::shared_ptr p1 = unwrap_shared_ptr< gtsam::Point3 >(in[1], "ptr_gtsamPoint3"); - boost::shared_ptr p2 = unwrap_shared_ptr< gtsam::Point3 >(in[2], "ptr_gtsamPoint3"); - pair< SharedPoint3, SharedPoint3 > pairResult = obj->return_ptrs(p1,p2); - out[0] = wrap_shared_ptr(pairResult.first,"gtsam.Point3", false); - out[1] = wrap_shared_ptr(pairResult.second,"gtsam.Point3", false); + Shared obj = unwrap_shared_ptr(in[0], "ptr_MyTemplateMatrix"); + boost::shared_ptr p1 = unwrap_shared_ptr< Matrix >(in[1], "ptr_Matrix"); + boost::shared_ptr p2 = unwrap_shared_ptr< Matrix >(in[2], "ptr_Matrix"); + pair< SharedMatrix, SharedMatrix > pairResult = obj->return_ptrs(p1,p2); + { + SharedMatrix* ret = new SharedMatrix(pairResult.first); + out[0] = wrap_shared_ptr(ret,"Matrix"); + } + { + SharedMatrix* ret = new SharedMatrix(pairResult.second); + out[1] = wrap_shared_ptr(ret,"Matrix"); + } } -void MyTemplatePoint3_templatedMethod_71(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void MyTemplateMatrix_templatedMethod_72(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { - typedef boost::shared_ptr Shared; + typedef boost::shared_ptr Shared; checkArguments("templatedMethodMatrix",nargout,nargin-1,1); - Shared obj = unwrap_shared_ptr(in[0], "ptr_MyTemplatePoint3"); + Shared obj = unwrap_shared_ptr(in[0], "ptr_MyTemplateMatrix"); Matrix& t = *unwrap_shared_ptr< Matrix >(in[1], "ptr_Matrix"); - obj->templatedMethod(t); + out[0] = wrap< Matrix >(obj->templatedMethod(t)); } -void MyTemplatePoint3_templatedMethod_72(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void MyTemplateMatrix_templatedMethod_73(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { - typedef boost::shared_ptr Shared; + typedef boost::shared_ptr SharedPoint2; + typedef boost::shared_ptr Shared; checkArguments("templatedMethodPoint2",nargout,nargin-1,1); - Shared obj = unwrap_shared_ptr(in[0], "ptr_MyTemplatePoint3"); + Shared obj = unwrap_shared_ptr(in[0], "ptr_MyTemplateMatrix"); gtsam::Point2& t = *unwrap_shared_ptr< gtsam::Point2 >(in[1], "ptr_gtsamPoint2"); - obj->templatedMethod(t); + out[0] = wrap_shared_ptr(SharedPoint2(new gtsam::Point2(obj->templatedMethod(t))),"gtsam.Point2", false); } -void MyTemplatePoint3_templatedMethod_73(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void MyTemplateMatrix_templatedMethod_74(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { - typedef boost::shared_ptr Shared; + typedef boost::shared_ptr SharedPoint3; + typedef boost::shared_ptr Shared; checkArguments("templatedMethodPoint3",nargout,nargin-1,1); - Shared obj = unwrap_shared_ptr(in[0], "ptr_MyTemplatePoint3"); + Shared obj = unwrap_shared_ptr(in[0], "ptr_MyTemplateMatrix"); gtsam::Point3& t = *unwrap_shared_ptr< gtsam::Point3 >(in[1], "ptr_gtsamPoint3"); - obj->templatedMethod(t); + out[0] = wrap_shared_ptr(SharedPoint3(new gtsam::Point3(obj->templatedMethod(t))),"gtsam.Point3", false); } -void MyTemplatePoint3_templatedMethod_74(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void MyTemplateMatrix_templatedMethod_75(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { - typedef boost::shared_ptr Shared; + typedef boost::shared_ptr Shared; checkArguments("templatedMethodVector",nargout,nargin-1,1); - Shared obj = unwrap_shared_ptr(in[0], "ptr_MyTemplatePoint3"); + Shared obj = unwrap_shared_ptr(in[0], "ptr_MyTemplateMatrix"); Vector& t = *unwrap_shared_ptr< Vector >(in[1], "ptr_Vector"); - obj->templatedMethod(t); + out[0] = wrap< Vector >(obj->templatedMethod(t)); } -void MyFactorPosePoint2_collectorInsertAndMakeBase_75(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void MyFactorPosePoint2_collectorInsertAndMakeBase_76(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { mexAtExit(&_deleteAllObjects); typedef boost::shared_ptr Shared; @@ -899,7 +923,7 @@ void MyFactorPosePoint2_collectorInsertAndMakeBase_75(int nargout, mxArray *out[ collector_MyFactorPosePoint2.insert(self); } -void MyFactorPosePoint2_constructor_76(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void MyFactorPosePoint2_constructor_77(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { mexAtExit(&_deleteAllObjects); typedef boost::shared_ptr Shared; @@ -914,7 +938,7 @@ void MyFactorPosePoint2_constructor_76(int nargout, mxArray *out[], int nargin, *reinterpret_cast (mxGetData(out[0])) = self; } -void MyFactorPosePoint2_deconstructor_77(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void MyFactorPosePoint2_deconstructor_78(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr Shared; checkArguments("delete_MyFactorPosePoint2",nargout,nargin,1); @@ -927,18 +951,18 @@ void MyFactorPosePoint2_deconstructor_77(int nargout, mxArray *out[], int nargin } } -void aGlobalFunction_78(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void aGlobalFunction_79(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { checkArguments("aGlobalFunction",nargout,nargin,0); out[0] = wrap< Vector >(aGlobalFunction()); } -void overloadedGlobalFunction_79(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void overloadedGlobalFunction_80(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_80(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void overloadedGlobalFunction_81(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { checkArguments("overloadedGlobalFunction",nargout,nargin,2); int a = unwrap< int >(in[0]); @@ -979,154 +1003,154 @@ void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) gtsamPoint2_dim_6(nargout, out, nargin-1, in+1); break; case 7: - gtsamPoint2_returnChar_7(nargout, out, nargin-1, in+1); + gtsamPoint2_eigenArguments_7(nargout, out, nargin-1, in+1); break; case 8: - gtsamPoint2_vectorConfusion_8(nargout, out, nargin-1, in+1); + gtsamPoint2_returnChar_8(nargout, out, nargin-1, in+1); break; case 9: - gtsamPoint2_x_9(nargout, out, nargin-1, in+1); + gtsamPoint2_vectorConfusion_9(nargout, out, nargin-1, in+1); break; case 10: - gtsamPoint2_y_10(nargout, out, nargin-1, in+1); + gtsamPoint2_x_10(nargout, out, nargin-1, in+1); break; case 11: - gtsamPoint3_collectorInsertAndMakeBase_11(nargout, out, nargin-1, in+1); + gtsamPoint2_y_11(nargout, out, nargin-1, in+1); break; case 12: - gtsamPoint3_constructor_12(nargout, out, nargin-1, in+1); + gtsamPoint3_collectorInsertAndMakeBase_12(nargout, out, nargin-1, in+1); break; case 13: - gtsamPoint3_deconstructor_13(nargout, out, nargin-1, in+1); + gtsamPoint3_constructor_13(nargout, out, nargin-1, in+1); break; case 14: - gtsamPoint3_norm_14(nargout, out, nargin-1, in+1); + gtsamPoint3_deconstructor_14(nargout, out, nargin-1, in+1); break; case 15: - gtsamPoint3_string_serialize_15(nargout, out, nargin-1, in+1); + gtsamPoint3_norm_15(nargout, out, nargin-1, in+1); break; case 16: - gtsamPoint3_StaticFunctionRet_16(nargout, out, nargin-1, in+1); + gtsamPoint3_string_serialize_16(nargout, out, nargin-1, in+1); break; case 17: - gtsamPoint3_staticFunction_17(nargout, out, nargin-1, in+1); + gtsamPoint3_StaticFunctionRet_17(nargout, out, nargin-1, in+1); break; case 18: - gtsamPoint3_string_deserialize_18(nargout, out, nargin-1, in+1); + gtsamPoint3_staticFunction_18(nargout, out, nargin-1, in+1); break; case 19: - Test_collectorInsertAndMakeBase_19(nargout, out, nargin-1, in+1); + gtsamPoint3_string_deserialize_19(nargout, out, nargin-1, in+1); break; case 20: - Test_constructor_20(nargout, out, nargin-1, in+1); + Test_collectorInsertAndMakeBase_20(nargout, out, nargin-1, in+1); break; case 21: Test_constructor_21(nargout, out, nargin-1, in+1); break; case 22: - Test_deconstructor_22(nargout, out, nargin-1, in+1); + Test_constructor_22(nargout, out, nargin-1, in+1); break; case 23: - Test_arg_EigenConstRef_23(nargout, out, nargin-1, in+1); + Test_deconstructor_23(nargout, out, nargin-1, in+1); break; case 24: - Test_create_MixedPtrs_24(nargout, out, nargin-1, in+1); + Test_arg_EigenConstRef_24(nargout, out, nargin-1, in+1); break; case 25: - Test_create_ptrs_25(nargout, out, nargin-1, in+1); + Test_create_MixedPtrs_25(nargout, out, nargin-1, in+1); break; case 26: - Test_print_26(nargout, out, nargin-1, in+1); + Test_create_ptrs_26(nargout, out, nargin-1, in+1); break; case 27: - Test_return_Point2Ptr_27(nargout, out, nargin-1, in+1); + Test_print_27(nargout, out, nargin-1, in+1); break; case 28: - Test_return_Test_28(nargout, out, nargin-1, in+1); + Test_return_Point2Ptr_28(nargout, out, nargin-1, in+1); break; case 29: - Test_return_TestPtr_29(nargout, out, nargin-1, in+1); + Test_return_Test_29(nargout, out, nargin-1, in+1); break; case 30: - Test_return_bool_30(nargout, out, nargin-1, in+1); + Test_return_TestPtr_30(nargout, out, nargin-1, in+1); break; case 31: - Test_return_double_31(nargout, out, nargin-1, in+1); + Test_return_bool_31(nargout, out, nargin-1, in+1); break; case 32: - Test_return_field_32(nargout, out, nargin-1, in+1); + Test_return_double_32(nargout, out, nargin-1, in+1); break; case 33: - Test_return_int_33(nargout, out, nargin-1, in+1); + Test_return_field_33(nargout, out, nargin-1, in+1); break; case 34: - Test_return_matrix1_34(nargout, out, nargin-1, in+1); + Test_return_int_34(nargout, out, nargin-1, in+1); break; case 35: - Test_return_matrix2_35(nargout, out, nargin-1, in+1); + Test_return_matrix1_35(nargout, out, nargin-1, in+1); break; case 36: - Test_return_pair_36(nargout, out, nargin-1, in+1); + Test_return_matrix2_36(nargout, out, nargin-1, in+1); break; case 37: - Test_return_ptrs_37(nargout, out, nargin-1, in+1); + Test_return_pair_37(nargout, out, nargin-1, in+1); break; case 38: - Test_return_size_t_38(nargout, out, nargin-1, in+1); + Test_return_ptrs_38(nargout, out, nargin-1, in+1); break; case 39: - Test_return_string_39(nargout, out, nargin-1, in+1); + Test_return_size_t_39(nargout, out, nargin-1, in+1); break; case 40: - Test_return_vector1_40(nargout, out, nargin-1, in+1); + Test_return_string_40(nargout, out, nargin-1, in+1); break; case 41: - Test_return_vector2_41(nargout, out, nargin-1, in+1); + Test_return_vector1_41(nargout, out, nargin-1, in+1); break; case 42: - MyBase_collectorInsertAndMakeBase_42(nargout, out, nargin-1, in+1); + Test_return_vector2_42(nargout, out, nargin-1, in+1); break; case 43: - MyBase_upcastFromVoid_43(nargout, out, nargin-1, in+1); + MyBase_collectorInsertAndMakeBase_43(nargout, out, nargin-1, in+1); break; case 44: - MyBase_deconstructor_44(nargout, out, nargin-1, in+1); + MyBase_upcastFromVoid_44(nargout, out, nargin-1, in+1); break; case 45: - MyTemplatePoint2_collectorInsertAndMakeBase_45(nargout, out, nargin-1, in+1); + MyBase_deconstructor_45(nargout, out, nargin-1, in+1); break; case 46: - MyTemplatePoint2_upcastFromVoid_46(nargout, out, nargin-1, in+1); + MyTemplatePoint2_collectorInsertAndMakeBase_46(nargout, out, nargin-1, in+1); break; case 47: - MyTemplatePoint2_constructor_47(nargout, out, nargin-1, in+1); + MyTemplatePoint2_upcastFromVoid_47(nargout, out, nargin-1, in+1); break; case 48: - MyTemplatePoint2_deconstructor_48(nargout, out, nargin-1, in+1); + MyTemplatePoint2_constructor_48(nargout, out, nargin-1, in+1); break; case 49: - MyTemplatePoint2_accept_T_49(nargout, out, nargin-1, in+1); + MyTemplatePoint2_deconstructor_49(nargout, out, nargin-1, in+1); break; case 50: - MyTemplatePoint2_accept_Tptr_50(nargout, out, nargin-1, in+1); + MyTemplatePoint2_accept_T_50(nargout, out, nargin-1, in+1); break; case 51: - MyTemplatePoint2_create_MixedPtrs_51(nargout, out, nargin-1, in+1); + MyTemplatePoint2_accept_Tptr_51(nargout, out, nargin-1, in+1); break; case 52: - MyTemplatePoint2_create_ptrs_52(nargout, out, nargin-1, in+1); + MyTemplatePoint2_create_MixedPtrs_52(nargout, out, nargin-1, in+1); break; case 53: - MyTemplatePoint2_return_T_53(nargout, out, nargin-1, in+1); + MyTemplatePoint2_create_ptrs_53(nargout, out, nargin-1, in+1); break; case 54: - MyTemplatePoint2_return_Tptr_54(nargout, out, nargin-1, in+1); + MyTemplatePoint2_return_T_54(nargout, out, nargin-1, in+1); break; case 55: - MyTemplatePoint2_return_ptrs_55(nargout, out, nargin-1, in+1); + MyTemplatePoint2_return_Tptr_55(nargout, out, nargin-1, in+1); break; case 56: - MyTemplatePoint2_templatedMethod_56(nargout, out, nargin-1, in+1); + MyTemplatePoint2_return_ptrs_56(nargout, out, nargin-1, in+1); break; case 57: MyTemplatePoint2_templatedMethod_57(nargout, out, nargin-1, in+1); @@ -1138,68 +1162,71 @@ void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) MyTemplatePoint2_templatedMethod_59(nargout, out, nargin-1, in+1); break; case 60: - MyTemplatePoint3_collectorInsertAndMakeBase_60(nargout, out, nargin-1, in+1); + MyTemplatePoint2_templatedMethod_60(nargout, out, nargin-1, in+1); break; case 61: - MyTemplatePoint3_upcastFromVoid_61(nargout, out, nargin-1, in+1); + MyTemplateMatrix_collectorInsertAndMakeBase_61(nargout, out, nargin-1, in+1); break; case 62: - MyTemplatePoint3_constructor_62(nargout, out, nargin-1, in+1); + MyTemplateMatrix_upcastFromVoid_62(nargout, out, nargin-1, in+1); break; case 63: - MyTemplatePoint3_deconstructor_63(nargout, out, nargin-1, in+1); + MyTemplateMatrix_constructor_63(nargout, out, nargin-1, in+1); break; case 64: - MyTemplatePoint3_accept_T_64(nargout, out, nargin-1, in+1); + MyTemplateMatrix_deconstructor_64(nargout, out, nargin-1, in+1); break; case 65: - MyTemplatePoint3_accept_Tptr_65(nargout, out, nargin-1, in+1); + MyTemplateMatrix_accept_T_65(nargout, out, nargin-1, in+1); break; case 66: - MyTemplatePoint3_create_MixedPtrs_66(nargout, out, nargin-1, in+1); + MyTemplateMatrix_accept_Tptr_66(nargout, out, nargin-1, in+1); break; case 67: - MyTemplatePoint3_create_ptrs_67(nargout, out, nargin-1, in+1); + MyTemplateMatrix_create_MixedPtrs_67(nargout, out, nargin-1, in+1); break; case 68: - MyTemplatePoint3_return_T_68(nargout, out, nargin-1, in+1); + MyTemplateMatrix_create_ptrs_68(nargout, out, nargin-1, in+1); break; case 69: - MyTemplatePoint3_return_Tptr_69(nargout, out, nargin-1, in+1); + MyTemplateMatrix_return_T_69(nargout, out, nargin-1, in+1); break; case 70: - MyTemplatePoint3_return_ptrs_70(nargout, out, nargin-1, in+1); + MyTemplateMatrix_return_Tptr_70(nargout, out, nargin-1, in+1); break; case 71: - MyTemplatePoint3_templatedMethod_71(nargout, out, nargin-1, in+1); + MyTemplateMatrix_return_ptrs_71(nargout, out, nargin-1, in+1); break; case 72: - MyTemplatePoint3_templatedMethod_72(nargout, out, nargin-1, in+1); + MyTemplateMatrix_templatedMethod_72(nargout, out, nargin-1, in+1); break; case 73: - MyTemplatePoint3_templatedMethod_73(nargout, out, nargin-1, in+1); + MyTemplateMatrix_templatedMethod_73(nargout, out, nargin-1, in+1); break; case 74: - MyTemplatePoint3_templatedMethod_74(nargout, out, nargin-1, in+1); + MyTemplateMatrix_templatedMethod_74(nargout, out, nargin-1, in+1); break; case 75: - MyFactorPosePoint2_collectorInsertAndMakeBase_75(nargout, out, nargin-1, in+1); + MyTemplateMatrix_templatedMethod_75(nargout, out, nargin-1, in+1); break; case 76: - MyFactorPosePoint2_constructor_76(nargout, out, nargin-1, in+1); + MyFactorPosePoint2_collectorInsertAndMakeBase_76(nargout, out, nargin-1, in+1); break; case 77: - MyFactorPosePoint2_deconstructor_77(nargout, out, nargin-1, in+1); + MyFactorPosePoint2_constructor_77(nargout, out, nargin-1, in+1); break; case 78: - aGlobalFunction_78(nargout, out, nargin-1, in+1); + MyFactorPosePoint2_deconstructor_78(nargout, out, nargin-1, in+1); break; case 79: - overloadedGlobalFunction_79(nargout, out, nargin-1, in+1); + aGlobalFunction_79(nargout, out, nargin-1, in+1); break; case 80: overloadedGlobalFunction_80(nargout, out, nargin-1, in+1); break; + case 81: + overloadedGlobalFunction_81(nargout, out, nargin-1, in+1); + break; } } catch(const std::exception& e) { mexErrMsgTxt(("Exception from gtsam:\n" + std::string(e.what()) + "\n").c_str()); diff --git a/wrap/tests/expected/overloadedGlobalFunction.m b/wrap/tests/expected/overloadedGlobalFunction.m index 04b12e081..16d24021e 100644 --- a/wrap/tests/expected/overloadedGlobalFunction.m +++ b/wrap/tests/expected/overloadedGlobalFunction.m @@ -1,8 +1,8 @@ function varargout = overloadedGlobalFunction(varargin) if length(varargin) == 1 && isa(varargin{1},'numeric') - varargout{1} = geometry_wrapper(79, varargin{:}); - elseif length(varargin) == 2 && isa(varargin{1},'numeric') && isa(varargin{2},'double') varargout{1} = geometry_wrapper(80, varargin{:}); + elseif length(varargin) == 2 && isa(varargin{1},'numeric') && isa(varargin{2},'double') + varargout{1} = geometry_wrapper(81, varargin{:}); else error('Arguments do not match any overload of function overloadedGlobalFunction'); end diff --git a/wrap/tests/testWrap.cpp b/wrap/tests/testWrap.cpp index 8f8c1994c..1a9c82143 100644 --- a/wrap/tests/testWrap.cpp +++ b/wrap/tests/testWrap.cpp @@ -454,7 +454,7 @@ TEST( wrap, matlab_code_geometry ) { EXPECT(files_equal(epath + "Test.m" , apath + "Test.m" )); EXPECT(files_equal(epath + "MyBase.m" , apath + "MyBase.m" )); EXPECT(files_equal(epath + "MyTemplatePoint2.m" , apath + "MyTemplatePoint2.m" )); - EXPECT(files_equal(epath + "MyTemplatePoint3.m" , apath + "MyTemplatePoint3.m" )); + EXPECT(files_equal(epath + "MyTemplateMatrix.m" , apath + "MyTemplateMatrix.m" )); EXPECT(files_equal(epath + "MyFactorPosePoint2.m" , apath + "MyFactorPosePoint2.m")); EXPECT(files_equal(epath + "aGlobalFunction.m" , apath + "aGlobalFunction.m" )); EXPECT(files_equal(epath + "overloadedGlobalFunction.m" , apath + "overloadedGlobalFunction.m" )); From 6b4d2321b48a566093427a5086d135ad6ccb5176 Mon Sep 17 00:00:00 2001 From: Paul Furgale Date: Mon, 1 Dec 2014 15:29:40 +0100 Subject: [PATCH 078/126] Fixed the prior factor to use charts and traits --- gtsam/slam/PriorFactor.h | 7 ++++--- 1 file changed, 4 insertions(+), 3 deletions(-) diff --git a/gtsam/slam/PriorFactor.h b/gtsam/slam/PriorFactor.h index 888dcb76b..bc5e9c87f 100644 --- a/gtsam/slam/PriorFactor.h +++ b/gtsam/slam/PriorFactor.h @@ -67,14 +67,14 @@ namespace gtsam { /** print */ virtual void print(const std::string& s, const KeyFormatter& keyFormatter = DefaultKeyFormatter) const { std::cout << s << "PriorFactor on " << keyFormatter(this->key()) << "\n"; - prior_.print(" prior mean: "); + traits::print()(prior_, " prior mean: "); this->noiseModel_->print(" noise model: "); } /** equals */ virtual bool equals(const NonlinearFactor& expected, double tol=1e-9) const { const This* e = dynamic_cast (&expected); - return e != NULL && Base::equals(*e, tol) && this->prior_.equals(e->prior_, tol); + return e != NULL && Base::equals(*e, tol) && traits::equals()(prior_, e->prior_, tol); } /** implement functions needed to derive from Factor */ @@ -83,7 +83,8 @@ namespace gtsam { Vector evaluateError(const T& p, boost::optional H = boost::none) const { if (H) (*H) = eye(p.dim()); // manifold equivalent of h(x)-z -> log(z,h(x)) - return prior_.localCoordinates(p); + DefaultChart chart; + return chart.local(prior_,p); } const VALUE & prior() const { return prior_; } From 1f171cf1a1d81c6d969305e4664e41226be92004 Mon Sep 17 00:00:00 2001 From: Christian Forster Date: Mon, 1 Dec 2014 10:56:55 -0500 Subject: [PATCH 079/126] Removed LieScalar from prior factor test and added new test for constructor with Vector3 --- gtsam/slam/tests/testPriorFactor.cpp | 14 ++++++++++---- 1 file changed, 10 insertions(+), 4 deletions(-) diff --git a/gtsam/slam/tests/testPriorFactor.cpp b/gtsam/slam/tests/testPriorFactor.cpp index b3e54bedb..d40ec3025 100644 --- a/gtsam/slam/tests/testPriorFactor.cpp +++ b/gtsam/slam/tests/testPriorFactor.cpp @@ -5,8 +5,8 @@ * @date Nov 4, 2014 */ +#include #include -#include #include using namespace std; @@ -14,10 +14,16 @@ using namespace gtsam; /* ************************************************************************* */ -// Constructor -TEST(PriorFactor, Constructor) { +// Constructor scalar +TEST(PriorFactor, ConstructorScalar) { SharedNoiseModel model; - PriorFactor factor(1, LieScalar(1.0), model); + PriorFactor factor(1, 1.0, model); +} + +// Constructor vector3 +TEST(PriorFactor, ConstructorVector3) { + SharedNoiseModel model = noiseModel::Isotropic::Sigma(3, 1.0); + PriorFactor factor(1, Vector3(1,2,3), model); } /* ************************************************************************* */ From c472c8673038d295e5a78ee7a23d296fedffff62 Mon Sep 17 00:00:00 2001 From: Christian Forster Date: Mon, 1 Dec 2014 12:10:45 -0500 Subject: [PATCH 080/126] get dimension of prior factor with traits --- gtsam/slam/PriorFactor.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/gtsam/slam/PriorFactor.h b/gtsam/slam/PriorFactor.h index bc5e9c87f..7f7aef8cb 100644 --- a/gtsam/slam/PriorFactor.h +++ b/gtsam/slam/PriorFactor.h @@ -81,7 +81,7 @@ namespace gtsam { /** vector of errors */ Vector evaluateError(const T& p, boost::optional H = boost::none) const { - if (H) (*H) = eye(p.dim()); + if (H) (*H) = eye(traits::dimension()); // manifold equivalent of h(x)-z -> log(z,h(x)) DefaultChart chart; return chart.local(prior_,p); From c7ab79690ba62e2a720a1204f61bf59e6a91cbed Mon Sep 17 00:00:00 2001 From: Christian Forster Date: Mon, 1 Dec 2014 12:38:17 -0500 Subject: [PATCH 081/126] missing for std::numeric_limits --- gtsam_unstable/nonlinear/ceres_rotation.h | 1 + 1 file changed, 1 insertion(+) diff --git a/gtsam_unstable/nonlinear/ceres_rotation.h b/gtsam_unstable/nonlinear/ceres_rotation.h index b02c10211..6ed3b88cb 100644 --- a/gtsam_unstable/nonlinear/ceres_rotation.h +++ b/gtsam_unstable/nonlinear/ceres_rotation.h @@ -47,6 +47,7 @@ #include #include +#include #include #define DCHECK assert From e9635121644d208735e77ffade7b5cb26ffc1aea Mon Sep 17 00:00:00 2001 From: dellaert Date: Mon, 1 Dec 2014 20:03:26 +0100 Subject: [PATCH 082/126] Tightened up individual Grammars --- wrap/Argument.h | 26 +++++++++++------------ wrap/Module.cpp | 2 +- wrap/Qualified.h | 43 +++++++++++++++++---------------------- wrap/ReturnValue.h | 6 ++---- wrap/Template.h | 13 +++++------- wrap/spirit.h | 18 ++++++++-------- wrap/tests/testMethod.cpp | 2 -- 7 files changed, 48 insertions(+), 62 deletions(-) diff --git a/wrap/Argument.h b/wrap/Argument.h index 98a8ab7b1..3b7a13ee3 100644 --- a/wrap/Argument.h +++ b/wrap/Argument.h @@ -129,7 +129,7 @@ struct ArgumentList: public std::vector { struct ArgumentGrammar: public classic::grammar { wrap::Argument& result_; ///< successful parse will be placed in here - TypeGrammar argument_type_g; + TypeGrammar argument_type_g; ///< Type parser for Argument::type /// Construct type grammar and specify where result is placed ArgumentGrammar(wrap::Argument& result) : @@ -138,15 +138,13 @@ struct ArgumentGrammar: public classic::grammar { /// Definition of type grammar template - struct definition: basic_rules { + struct definition: BasicRules { typedef classic::rule Rule; - Rule argument_p, argumentList_p; + Rule argument_p; definition(ArgumentGrammar const& self) { - - using namespace wrap; using namespace classic; // NOTE: allows for pointers to all types @@ -156,7 +154,7 @@ struct ArgumentGrammar: public classic::grammar { >> self.argument_type_g // >> !ch_p('*')[assign_a(self.result_.is_ptr, T)] >> !ch_p('&')[assign_a(self.result_.is_ref, T)] - >> basic_rules::name_p[assign_a(self.result_.name)]; + >> BasicRules::name_p[assign_a(self.result_.name)]; } Rule const& start() const { @@ -173,9 +171,9 @@ struct ArgumentListGrammar: public classic::grammar { wrap::ArgumentList& result_; ///< successful parse will be placed in here - const Argument arg0; // used to reset arg - mutable Argument arg; // temporary argument for use during parsing - ArgumentGrammar argument_g; + const Argument arg0; ///< used to reset arg + mutable Argument arg; ///< temporary argument for use during parsing + ArgumentGrammar argument_g; ///< single Argument parser /// Construct type grammar and specify where result is placed ArgumentListGrammar(wrap::ArgumentList& result) : @@ -184,21 +182,21 @@ struct ArgumentListGrammar: public classic::grammar { /// Definition of type grammar template - struct definition: basic_rules { + struct definition { - typedef classic::rule Rule; - - Rule argument_p, argumentList_p; + classic::rule argument_p, argumentList_p; definition(ArgumentListGrammar const& self) { using namespace classic; + argument_p = self.argument_g // [classic::push_back_a(self.result_, self.arg)] // [assign_a(self.arg, self.arg0)]; + argumentList_p = '(' >> !argument_p >> *(',' >> argument_p) >> ')'; } - Rule const& start() const { + classic::rule const& start() const { return argumentList_p; } diff --git a/wrap/Module.cpp b/wrap/Module.cpp index d7059d316..decc390d6 100644 --- a/wrap/Module.cpp +++ b/wrap/Module.cpp @@ -109,7 +109,7 @@ void Module::parseMarkup(const std::string& data) { // Define Rule and instantiate basic rules typedef rule Rule; - basic_rules basic; + BasicRules basic; // TODO, do we really need cls here? Non-local Class cls0(verbose),cls(verbose); diff --git a/wrap/Qualified.h b/wrap/Qualified.h index 29b961518..000d749ec 100644 --- a/wrap/Qualified.h +++ b/wrap/Qualified.h @@ -35,7 +35,7 @@ public: std::vector namespaces_; ///< Stack of namespaces std::string name_; ///< type name - friend class TypeGrammar; + friend struct TypeGrammar; friend class TemplateSubstitution; public: @@ -81,7 +81,7 @@ public: // Qualified is 'abused' as template argument name as well // this function checks whether *this matches with templateArg bool match(const std::string& templateArg) const { - return (name_ == templateArg && namespaces_.empty());//TODO && category == CLASS); + return (name_ == templateArg && namespaces_.empty()); //TODO && category == CLASS); } void rename(const Qualified& q) { @@ -128,7 +128,6 @@ public: return Qualified("void", VOID); } - /// Return a qualified string using given delimiter std::string qualifiedName(const std::string& delimiter = "") const { std::string result; @@ -156,12 +155,10 @@ public: /* ************************************************************************* */ // http://boost-spirit.com/distrib/spirit_1_8_2/libs/spirit/doc/grammar.html -class TypeGrammar: public classic::grammar { +struct TypeGrammar: classic::grammar { wrap::Qualified& result_; ///< successful parse will be placed in here -public: - /// Construct type grammar and specify where result is placed TypeGrammar(wrap::Qualified& result) : result_(result) { @@ -169,17 +166,17 @@ public: /// Definition of type grammar template - struct definition: basic_rules { + struct definition: BasicRules { typedef classic::rule Rule; - Rule void_p, my_basisType_p, my_eigenType_p, namespace_del_p, class_p, - type_p; + Rule void_p, basisType_p, eigenType_p, namespace_del_p, class_p, type_p; definition(TypeGrammar const& self) { using namespace wrap; using namespace classic; + typedef BasicRules Basic; // HACK: use const values instead of using enums themselves - somehow this doesn't result in values getting assigned to gibberish static const Qualified::Category EIGEN = Qualified::EIGEN; @@ -187,25 +184,26 @@ public: static const Qualified::Category CLASS = Qualified::CLASS; static const Qualified::Category VOID = Qualified::VOID; - void_p = str_p("void")[assign_a(self.result_.name_)] // + void_p = str_p("void") // + [assign_a(self.result_.name_)] // [assign_a(self.result_.category, VOID)]; - my_basisType_p = basic_rules::basisType_p // + basisType_p = Basic::basisType_p // [assign_a(self.result_.name_)] // [assign_a(self.result_.category, BASIS)]; - my_eigenType_p = basic_rules::eigenType_p // + eigenType_p = Basic::eigenType_p // [assign_a(self.result_.name_)] // [assign_a(self.result_.category, EIGEN)]; - namespace_del_p = basic_rules::namespace_p // + namespace_del_p = Basic::namespace_p // [push_back_a(self.result_.namespaces_)] >> str_p("::"); - class_p = *namespace_del_p >> basic_rules::className_p // + class_p = *namespace_del_p >> Basic::className_p // [assign_a(self.result_.name_)] // [assign_a(self.result_.category, CLASS)]; - type_p = void_p | my_basisType_p | class_p | my_eigenType_p; + type_p = void_p | basisType_p | class_p | eigenType_p; } Rule const& start() const { @@ -218,8 +216,8 @@ public: /* ************************************************************************* */ // http://boost-spirit.com/distrib/spirit_1_8_2/libs/spirit/doc/grammar.html -template -struct TypeListGrammar: public classic::grammar > { +template +struct TypeListGrammar: public classic::grammar > { typedef std::vector TypeList; TypeList& result_; ///< successful parse will be placed in here @@ -234,11 +232,9 @@ struct TypeListGrammar: public classic::grammar > { /// Definition of type grammar template - struct definition: basic_rules { + struct definition { - typedef classic::rule Rule; - - Rule type_p, typeList_p; + classic::rule type_p, typeList_p; definition(TypeListGrammar const& self) { using namespace classic; @@ -248,7 +244,7 @@ struct TypeListGrammar: public classic::grammar > { typeList_p = OPEN >> !type_p >> *(',' >> type_p) >> CLOSE; } - Rule const& start() const { + classic::rule const& start() const { return typeList_p; } @@ -260,6 +256,5 @@ struct TypeListGrammar: public classic::grammar > { // Needed for other parsers in Argument.h and ReturnType.h static const bool T = true; - -}// \namespace wrap +} // \namespace wrap diff --git a/wrap/ReturnValue.h b/wrap/ReturnValue.h index b23cbf681..629684a34 100644 --- a/wrap/ReturnValue.h +++ b/wrap/ReturnValue.h @@ -82,8 +82,7 @@ struct ReturnValue { struct ReturnValueGrammar: public classic::grammar { wrap::ReturnValue& result_; ///< successful parse will be placed in here - - ReturnTypeGrammar returnType1_g, returnType2_g; + ReturnTypeGrammar returnType1_g, returnType2_g; ///< Type parsers /// Construct type grammar and specify where result is placed ReturnValueGrammar(wrap::ReturnValue& result) : @@ -97,7 +96,6 @@ struct ReturnValueGrammar: public classic::grammar { classic::rule pair_p, returnValue_p; definition(ReturnValueGrammar const& self) { - using namespace classic; pair_p = (str_p("pair") >> '<' >> self.returnType1_g >> ',' @@ -114,4 +112,4 @@ struct ReturnValueGrammar: public classic::grammar { }; // ReturnValueGrammar -} // \namespace wrap +}// \namespace wrap diff --git a/wrap/Template.h b/wrap/Template.h index c9edcaf2b..cfa0db008 100644 --- a/wrap/Template.h +++ b/wrap/Template.h @@ -37,8 +37,7 @@ struct Template { struct TemplateGrammar: public classic::grammar { Template& result_; ///< successful parse will be placed in here - - TypeListGrammar<'{', '}'> argValues_g; + TypeListGrammar<'{', '}'> argValues_g; ///< TypeList parser /// Construct type grammar and specify where result is placed TemplateGrammar(Template& result) : @@ -47,20 +46,18 @@ struct TemplateGrammar: public classic::grammar { /// Definition of type grammar template - struct definition: basic_rules { + struct definition: BasicRules { - typedef classic::rule Rule; - - Rule templateArgValues_p; + classic::rule templateArgValues_p; definition(TemplateGrammar const& self) { using namespace classic; templateArgValues_p = (str_p("template") >> '<' - >> (basic_rules::name_p)[assign_a(self.result_.argName)] + >> (BasicRules::name_p)[assign_a(self.result_.argName)] >> '=' >> self.argValues_g >> '>'); } - Rule const& start() const { + classic::rule const& start() const { return templateArgValues_p; } diff --git a/wrap/spirit.h b/wrap/spirit.h index 4a18b53e8..92abe93ef 100644 --- a/wrap/spirit.h +++ b/wrap/spirit.h @@ -43,7 +43,7 @@ BOOST_SPIRIT_CLASSIC_NAMESPACE_BEGIN /////////////////////////////////////////////////////////////////////////// struct pop_action { - template< typename T> + template< typename T> void act(T& ref_) const { if (!ref_.empty()) @@ -86,7 +86,7 @@ inline ref_actor pop_a(T& ref_) struct append_action { - template< typename T, typename ValueT > + template< typename T, typename ValueT > void act(T& ref_, ValueT const& value_) const { ref_.insert(ref_.begin(), value_.begin(), value_.end()); @@ -125,18 +125,18 @@ BOOST_SPIRIT_CLASSIC_NAMESPACE_END } } +namespace wrap { + namespace classic = BOOST_SPIRIT_CLASSIC_NS; /// Some basic rules used by all parsers template -struct basic_rules { +struct BasicRules { - typedef BOOST_SPIRIT_CLASSIC_NS::rule Rule; + classic::rule comments_p, basisType_p, eigenType_p, keywords_p, + stlType_p, name_p, className_p, namespace_p; - Rule comments_p, basisType_p, eigenType_p, keywords_p, stlType_p, name_p, - className_p, namespace_p; - - basic_rules() { + BasicRules() { using namespace BOOST_SPIRIT_CLASSIC_NS; @@ -160,5 +160,5 @@ struct basic_rules { namespace_p = lexeme_d[lower_p >> *(alnum_p | '_')] - keywords_p; } }; - +} diff --git a/wrap/tests/testMethod.cpp b/wrap/tests/testMethod.cpp index bc21b332c..5b58fa31e 100644 --- a/wrap/tests/testMethod.cpp +++ b/wrap/tests/testMethod.cpp @@ -65,8 +65,6 @@ TEST( Method, addOverload ) { // template // struct definition: basic_rules { // -// typedef classic::rule Rule; -// // Rule templateArgValue_p, templateArgValues_p, argument_p, argumentList_p, // returnType1_p, returnType2_p, pair_p, returnValue_p, methodName_p, // method_p; From de650069e2f2a3a952b63db46e1cbb3005b625d3 Mon Sep 17 00:00:00 2001 From: dellaert Date: Mon, 1 Dec 2014 20:29:11 +0100 Subject: [PATCH 083/126] No using namespace in headers --- wrap/spirit.h | 9 ++++++++- 1 file changed, 8 insertions(+), 1 deletion(-) diff --git a/wrap/spirit.h b/wrap/spirit.h index 92abe93ef..ca081109a 100644 --- a/wrap/spirit.h +++ b/wrap/spirit.h @@ -138,7 +138,14 @@ struct BasicRules { BasicRules() { - using namespace BOOST_SPIRIT_CLASSIC_NS; + using classic::comment_p; + using classic::eol_p; + using classic::str_p; + using classic::alpha_p; + using classic::lexeme_d; + using classic::upper_p; + using classic::lower_p; + using classic::alnum_p; comments_p = comment_p("/*", "*/") | comment_p("//", eol_p); From aceeb2037b3c9edbe29d259dffde7ea53deb5f86 Mon Sep 17 00:00:00 2001 From: dellaert Date: Mon, 1 Dec 2014 20:29:35 +0100 Subject: [PATCH 084/126] Template tightening --- wrap/Class.cpp | 6 ++--- wrap/Module.cpp | 4 +-- wrap/Template.h | 53 ++++++++++++++++++++++++++++++------- wrap/tests/testClass.cpp | 19 +++++-------- wrap/tests/testTemplate.cpp | 35 ++++++++++++++++-------- 5 files changed, 79 insertions(+), 38 deletions(-) diff --git a/wrap/Class.cpp b/wrap/Class.cpp index 09433d616..6e415065d 100644 --- a/wrap/Class.cpp +++ b/wrap/Class.cpp @@ -319,11 +319,11 @@ void Class::addMethod(bool verbose, bool is_const, Str methodName, const ArgumentList& argumentList, const ReturnValue& returnValue, const Template& tmplate) { // Check if templated - if (!tmplate.argName.empty() && tmplate.argValues.size() > 0) { + if (tmplate.valid()) { // Create method to expand // For all values of the template argument, create a new method - BOOST_FOREACH(const Qualified& instName, tmplate.argValues) { - const TemplateSubstitution ts(tmplate.argName, instName, *this); + BOOST_FOREACH(const Qualified& instName, tmplate.argValues()) { + const TemplateSubstitution ts(tmplate.argName(), instName, *this); // substitute template in arguments ArgumentList expandedArgs = argumentList.expandTemplate(ts); // do the same for return type diff --git a/wrap/Module.cpp b/wrap/Module.cpp index decc390d6..917130f5c 100644 --- a/wrap/Module.cpp +++ b/wrap/Module.cpp @@ -200,7 +200,7 @@ void Module::parseMarkup(const std::string& data) { Rule class_p = eps_p[assign_a(cls,cls0)] >> (!(classTemplate_g - [push_back_a(cls.templateArgs, classTemplate.argName)] + [push_back_a(cls.templateArgs, classTemplate.argName())] | templateList_p) >> !(str_p("virtual")[assign_a(cls.isVirtual, true)]) >> str_p("class") @@ -216,7 +216,7 @@ void Module::parseMarkup(const std::string& data) { [assign_a(cls.namespaces_, namespaces)] [assign_a(cls.deconstructor.name,cls.name_)] [bl::bind(&handle_possible_template, bl::var(classes), bl::var(cls), - bl::var(classTemplate.argValues))] + bl::var(classTemplate.argValues()))] [clear_a(classTemplate)] [assign_a(constructor, constructor0)] [assign_a(cls,cls0)]; diff --git a/wrap/Template.h b/wrap/Template.h index cfa0db008..5a64412ed 100644 --- a/wrap/Template.h +++ b/wrap/Template.h @@ -23,13 +23,34 @@ namespace wrap { /// The template specification that goes before a method or a class -struct Template { - std::string argName; - std::vector argValues; - void clear() { - argName.clear(); - argValues.clear(); +class Template { + std::string argName_; + std::vector argValues_; + friend struct TemplateGrammar; +public: + /// The only way to get values into a Template is via our friendly Grammar + Template() { } + void clear() { + argName_.clear(); + argValues_.clear(); + } + const std::string& argName() const { + return argName_; + } + const std::vector& argValues() const { + return argValues_; + } + size_t nrValues() const { + return argValues_.size(); + } + const Qualified& operator[](size_t i) const { + return argValues_[i]; + } + bool valid() const { + return !argName_.empty() && argValues_.size() > 0; + } + }; /* ************************************************************************* */ @@ -41,7 +62,7 @@ struct TemplateGrammar: public classic::grammar { /// Construct type grammar and specify where result is placed TemplateGrammar(Template& result) : - result_(result), argValues_g(result.argValues) { + result_(result), argValues_g(result.argValues_) { } /// Definition of type grammar @@ -51,9 +72,10 @@ struct TemplateGrammar: public classic::grammar { classic::rule templateArgValues_p; definition(TemplateGrammar const& self) { - using namespace classic; + using classic::str_p; + using classic::assign_a; templateArgValues_p = (str_p("template") >> '<' - >> (BasicRules::name_p)[assign_a(self.result_.argName)] + >> (BasicRules::name_p)[assign_a(self.result_.argName_)] >> '=' >> self.argValues_g >> '>'); } @@ -65,5 +87,16 @@ struct TemplateGrammar: public classic::grammar { }; // TemplateGrammar -}// \namespace wrap +/// Cool initializer for tests +static inline boost::optional