diff --git a/.cproject b/.cproject index 075558734..b31515394 100644 --- a/.cproject +++ b/.cproject @@ -308,6 +308,14 @@ true true + + make + -j2 + testGaussianFactor.run + true + true + true + make -j2 @@ -334,7 +342,6 @@ make - tests/testBayesTree.run true false @@ -342,7 +349,6 @@ make - testBinaryBayesNet.run true false @@ -390,7 +396,6 @@ make - testSymbolicBayesNet.run true false @@ -398,7 +403,6 @@ make - tests/testSymbolicFactor.run true false @@ -406,7 +410,6 @@ make - testSymbolicFactorGraph.run true false @@ -422,20 +425,11 @@ make - tests/testBayesTree true false true - - make - -j2 - testGaussianFactor.run - true - true - true - make -j5 @@ -524,22 +518,6 @@ false true - - make - -j2 - tests/testPose2.run - true - true - true - - - make - -j2 - tests/testPose3.run - true - true - true - make -j2 @@ -556,6 +534,22 @@ true true + + make + -j2 + tests/testPose2.run + true + true + true + + + make + -j2 + tests/testPose3.run + true + true + true + make -j2 @@ -580,26 +574,26 @@ true true - + make - -j2 - all + -j5 + testValues.run true true true - + make - -j2 - check + -j5 + testOrdering.run true true true - + make - -j2 - clean + -j5 + testKey.run true true true @@ -684,26 +678,26 @@ true true - + make - -j5 - testValues.run + -j2 + all true true true - + make - -j5 - testOrdering.run + -j2 + check true true true - + make - -j5 - testKey.run + -j2 + clean true true true @@ -958,7 +952,6 @@ make - testGraph.run true false @@ -966,7 +959,6 @@ make - testJunctionTree.run true false @@ -974,7 +966,6 @@ make - testSymbolicBayesNetB.run true false @@ -1110,7 +1101,6 @@ make - testErrors.run true false @@ -1574,6 +1564,7 @@ make + testSimulated2DOriented.run true false @@ -1613,6 +1604,7 @@ make + testSimulated2D.run true false @@ -1620,6 +1612,7 @@ make + testSimulated3D.run true false @@ -1835,6 +1828,7 @@ make + tests/testGaussianISAM2 true false @@ -1856,6 +1850,102 @@ true true + + make + -j2 + testRot3.run + true + true + true + + + make + -j2 + testRot2.run + true + true + true + + + make + -j2 + testPose3.run + true + true + true + + + make + -j2 + timeRot3.run + true + true + true + + + make + -j2 + testPose2.run + true + true + true + + + make + -j2 + testCal3_S2.run + true + true + true + + + make + -j2 + testSimpleCamera.run + true + true + true + + + make + -j2 + testHomography2.run + true + true + true + + + make + -j2 + testCalibratedCamera.run + true + true + true + + + make + -j2 + check + true + true + true + + + make + -j2 + clean + true + true + true + + + make + -j2 + testPoint2.run + true + true + true + make -j2 @@ -2057,7 +2147,6 @@ cpack - -G DEB true false @@ -2065,7 +2154,6 @@ cpack - -G RPM true false @@ -2073,7 +2161,6 @@ cpack - -G TGZ true false @@ -2081,7 +2168,6 @@ cpack - --config CPackSourceConfig.cmake true false @@ -2207,98 +2293,34 @@ true true - + make - -j2 - testRot3.run + -j5 + testSpirit.run true true true - + make - -j2 - testRot2.run + -j5 + testWrap.run true true true - + make - -j2 - testPose3.run + -j5 + check.wrap true true true - + make - -j2 - timeRot3.run - true - true - true - - - make - -j2 - testPose2.run - true - true - true - - - make - -j2 - testCal3_S2.run - true - true - true - - - make - -j2 - testSimpleCamera.run - true - true - true - - - make - -j2 - testHomography2.run - true - true - true - - - make - -j2 - testCalibratedCamera.run - true - true - true - - - make - -j2 - check - true - true - true - - - make - -j2 - clean - true - true - true - - - make - -j2 - testPoint2.run + -j5 + wrap true true true @@ -2342,46 +2364,7 @@ false true - - make - -j5 - testSpirit.run - true - true - true - - - make - -j5 - testWrap.run - true - true - true - - - make - -j5 - check.wrap - true - true - true - - - make - -j5 - wrap_gtsam - true - true - true - - - make - -j5 - wrap - true - true - true - + diff --git a/CMakeLists.txt b/CMakeLists.txt index 77b8b0c18..ed6b31db9 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -36,41 +36,47 @@ else() set(GTSAM_UNSTABLE_AVAILABLE 0) endif() + # Configurable Options option(GTSAM_BUILD_TESTS "Enable/Disable building of tests" ON) option(GTSAM_BUILD_TIMING "Enable/Disable building of timing scripts" ON) option(GTSAM_BUILD_EXAMPLES "Enable/Disable building of examples" ON) if(GTSAM_UNSTABLE_AVAILABLE) - option(GTSAM_BUILD_UNSTABLE "Enable/Disable libgtsam_unstable" OFF) + option(GTSAM_BUILD_UNSTABLE "Enable/Disable libgtsam_unstable" ON) endif() -option(GTSAM_BUILD_WRAP "Enable/Disable building of matlab wrap utility (necessary for matlab interface)" ON) -if(MSVC) - option(GTSAM_BUILD_SHARED_LIBRARY "Enable/Disable building of a shared version of gtsam" OFF) -else() +if(NOT MSVC) option(GTSAM_BUILD_SHARED_LIBRARY "Enable/Disable building of a shared version of gtsam" ON) -endif() -option(GTSAM_BUILD_STATIC_LIBRARY "Enable/Disable building of a static version of gtsam" ON) -option(GTSAM_USE_QUATERNIONS "Enable/Disable using an internal Quaternion representation for rotations instead of rotation matrices" OFF) -if(MSVC) - option(GTSAM_BUILD_CONVENIENCE_LIBRARIES "Enable/Disable use of convenience libraries for faster development rebuilds, but slower install" OFF) + option(GTSAM_BUILD_STATIC_LIBRARY "Enable/Disable building of a static version of gtsam" ON) else() + set(GTSAM_BUILD_STATIC_LIBRARY ON) +endif() +option(GTSAM_USE_QUATERNIONS "Enable/Disable using an internal Quaternion representation for rotations instead of rotation matrices" OFF) +if(NOT MSVC) option(GTSAM_BUILD_CONVENIENCE_LIBRARIES "Enable/Disable use of convenience libraries for faster development rebuilds, but slower install" ON) endif() -option(GTSAM_INSTALL_MATLAB_TOOLBOX "Enable/Disable installation of matlab toolbox" ON) -option(GTSAM_INSTALL_MATLAB_EXAMPLES "Enable/Disable installation of matlab examples" ON) -option(GTSAM_INSTALL_MATLAB_TESTS "Enable/Disable installation of matlab tests" ON) -option(GTSAM_INSTALL_WRAP "Enable/Disable installation of wrap utility" ON) -set(GTSAM_TOOLBOX_INSTALL_PATH ${CMAKE_INSTALL_PREFIX}/borg/toolbox CACHE DOCSTRING "Path to install matlab toolbox") -set(GTSAM_WRAP_HEADER_PATH ${PROJECT_SOURCE_DIR}/wrap CACHE DOCSTRING "Path to directory of matlab.h") +# Options relating to MATLAB wrapper # TODO: Check for matlab mex binary before handling building of binaries +option(GTSAM_INSTALL_MATLAB_TOOLBOX "Enable/Disable installation of matlab toolbox" ON) +option(GTSAM_BUILD_WRAP "Enable/Disable building of matlab wrap utility (necessary for matlab interface)" ON) +option(GTSAM_INSTALL_WRAP "Enable/Disable installation of wrap utility for wrapping other libraries" ON) +set(GTSAM_TOOLBOX_INSTALL_PATH "" CACHE DOCSTRING "Matlab toolbox destination, blank defaults to CMAKE_INSTALL_PREFIX/borg/toolbox") +set(GTSAM_BUILD_MEX_BINARY_FLAGS "" CACHE STRING "Extra flags for running Matlab MEX compilation") +set(MEX_COMMAND "mex" CACHE FILEPATH "Command to use for executing mex (if on path, 'mex' will work)") + +# Check / set dependent variables for MATLAB wrapper +set(GTSAM_WRAP_HEADER_PATH "${PROJECT_SOURCE_DIR}/wrap") +if(GTSAM_INSTALL_MATLAB_TOOLBOX AND NOT GTSAM_BUILD_WRAP) + message(FATAL_ERROR "GTSAM_INSTALL_MATLAB_TOOLBOX is enabled, please also enable GTSAM_BUILD_WRAP") +endif() +if(GTSAM_INSTALL_WRAP AND NOT GTSAM_BUILD_WRAP) + message(FATAL_ERROR "GTSAM_INSTALL_WRAP is enabled, please also enable GTSAM_BUILD_WRAP") +endif() +if(NOT GTSAM_TOOLBOX_INSTALL_PATH) + set(GTSAM_TOOLBOX_INSTALL_PATH "${CMAKE_INSTALL_PREFIX}/borg/toolbox") +endif() -# Flags for building/installing mex files -option(GTSAM_BUILD_MEX_BIN "Enable/Disable building of matlab mex files" OFF) -option(GTSAM_INSTALL_MEX_BIN "Enable/Disable installing matlab mex binaries" OFF) -set(GTSAM_BUILD_MEX_BINARY_FLAGS "" CACHE STRING "Flags for running Matlab MEX compilation") -set(MEX_COMMAND "mex" CACHE STRING "Command to use for executing mex (if on path, 'mex' will work)") # Flags for choosing default packaging tools set(CPACK_SOURCE_GENERATOR "TGZ" CACHE STRING "CPack Default Source Generator") @@ -90,7 +96,7 @@ endif(GTSAM_USE_QUATERNIONS) # Flags to determine whether tests and examples are build during 'make install' # Note that these remove the targets from the 'all' option(GTSAM_DISABLE_TESTS_ON_INSTALL "Disables building tests during install" ON) -option(GTSAM_DISABLE_EXAMPLES_ON_INSTALL "Disables buildint examples during install" OFF) +option(GTSAM_DISABLE_EXAMPLES_ON_INSTALL "Disables building examples during install" OFF) # Pull in infrastructure if (GTSAM_BUILD_TESTS) @@ -103,7 +109,8 @@ endif() if(CYGWIN OR MSVC OR WIN32) set(Boost_USE_STATIC_LIBS 1) endif() -find_package(Boost 1.43 COMPONENTS serialization REQUIRED) +find_package(Boost 1.43 COMPONENTS serialization system filesystem thread date_time REQUIRED) +set(GTSAM_BOOST_LIBRARIES ${Boost_SERIALIZATION_LIBRARY}) # General build settings include_directories( @@ -134,7 +141,9 @@ if (GTSAM_BUILD_EXAMPLES) endif(GTSAM_BUILD_EXAMPLES) # Matlab toolbox -add_subdirectory(matlab) +if (GTSAM_INSTALL_MATLAB_TOOLBOX) + add_subdirectory(matlab) +endif() # Build gtsam_unstable if (GTSAM_BUILD_UNSTABLE) @@ -168,11 +177,12 @@ message(STATUS "Build flags ") print_config_flag(${GTSAM_BUILD_TIMING} "Build Timing scripts ") print_config_flag(${GTSAM_BUILD_EXAMPLES} "Build Examples ") print_config_flag(${GTSAM_BUILD_TESTS} "Build Tests ") -print_config_flag(${GTSAM_BUILD_WRAP} "Build Wrap ") -print_config_flag(${GTSAM_BUILD_SHARED_LIBRARY} "Build shared GTSAM Library ") -print_config_flag(${GTSAM_BUILD_STATIC_LIBRARY} "Build static GTSAM Library ") +if(NOT MSVC) + print_config_flag(${GTSAM_BUILD_SHARED_LIBRARY} "Build shared GTSAM Library ") + print_config_flag(${GTSAM_BUILD_STATIC_LIBRARY} "Build static GTSAM Library ") + print_config_flag(${GTSAM_BUILD_CONVENIENCE_LIBRARIES} "Build Convenience Libraries ") +endif() print_config_flag(${GTSAM_BUILD_TYPE_POSTFIXES} "Put build-type in library name ") -print_config_flag(${GTSAM_BUILD_CONVENIENCE_LIBRARIES} "Build Convenience Libraries ") if(GTSAM_UNSTABLE_AVAILABLE) print_config_flag(${GTSAM_BUILD_UNSTABLE} "Build libgtsam_unstable ") endif() @@ -192,11 +202,8 @@ print_config_flag(${GTSAM_USE_QUATERNIONS} "Quaternions as default R message(STATUS "MATLAB toolbox flags ") print_config_flag(${GTSAM_INSTALL_MATLAB_TOOLBOX} "Install matlab toolbox ") -print_config_flag(${GTSAM_INSTALL_MATLAB_EXAMPLES} "Install matlab examples ") -print_config_flag(${GTSAM_INSTALL_MATLAB_TESTS} "Install matlab tests ") +print_config_flag(${GTSAM_BUILD_WRAP} "Build Wrap ") print_config_flag(${GTSAM_INSTALL_WRAP} "Install wrap utility ") -print_config_flag(${GTSAM_BUILD_MEX_BIN} "Build MEX binaries ") -print_config_flag(${GTSAM_INSTALL_MEX_BIN} "Install MEX binaries ") message(STATUS "===============================================================") # Include CPack *after* all flags diff --git a/gtsam.h b/gtsam.h index 48199cbf3..882319607 100644 --- a/gtsam.h +++ b/gtsam.h @@ -6,19 +6,26 @@ * * Requirements: * Classes must start with an uppercase letter - * Only one Method/Constructor per line + * - Can wrap a typedef + * Only one Method/Constructor per line, though methods/constructors can extend across multiple lines * Methods can return * - Eigen types: Matrix, Vector * - C/C++ basic types: string, bool, size_t, size_t, double, char, unsigned char * - void * - Any class with which be copied with boost::make_shared() * - boost::shared_ptr of any object type - * Limitations on methods - * - Parsing does not support overloading - * - There can only be one method (static or otherwise) with a given name + * Constructors + * - Overloads are supported + * - A class with no constructors can be returned from other functions but not allocated directly in MATLAB + * Methods * - Constness has no effect - * Methods must start with a lowercase letter - * Static methods must start with a letter (upper or lowercase) and use the "static" keyword + * - Specify by-value (not reference) return types, even if C++ method returns reference + * - Must start with a lowercase letter + * - Overloads are supported + * Static methods + * - Must start with a letter (upper or lowercase) and use the "static" keyword + * - The first letter will be made uppercase in the generated MATLAB interface + * - Overloads are supported * Arguments to functions any of * - Eigen types: Matrix, Vector * - Eigen types and classes as an optionally const reference @@ -35,7 +42,7 @@ * Namespace usage * - Namespaces can be specified for classes in arguments and return values * - In each case, the namespace must be fully specified, e.g., "namespace1::namespace2::ClassName" - * Using namespace + * Using namespace: FIXME: this functionality is currently broken * - To use a namespace (e.g., generate a "using namespace x" line in cpp files), add "using namespace x;" * - This declaration applies to all classes *after* the declaration, regardless of brackets * Includes in C++ wrappers @@ -44,17 +51,34 @@ * - To override, add a full include statement just before the class statement * - An override include can be added for a namespace by placing it just before the namespace statement * - Both classes and namespace accept exactly one namespace - * Overriding type dependency checks + * Using classes defined in other modules * - If you are using a class 'OtherClass' not wrapped in this definition file, add "class OtherClass;" to avoid a dependency error - * - Limitation: this only works if the class does not need a namespace specification + * Virtual inheritance + * - Specify fully-qualified base classes, i.e. "virtual class Derived : module::Base {" + * - Mark with 'virtual' keyword, e.g. "virtual class Base {", and also "virtual class Derived : module::Base {" + * - Forward declarations must also be marked virtual, e.g. "virtual class module::Base;" and + * also "virtual class module::Derived;" + * - Pure virtual (abstract) classes should list no constructors in this interface file + * - Virtual classes must have a clone() function in C++ (though it does not have to be included + * in the MATLAB interface). clone() will be called whenever an object copy is needed, instead + * of using the copy constructor (which is used for non-virtual objects). + * Templates + * - Basic templates are supported either with an explicit list of types to instantiate, + * e.g. template class Class1 { ... }; + * or with typedefs, e.g. + * template class Class2 { ... }; + * typedef Class2 MyInstantiatedClass; + * - To create new instantiations in other modules, you must copy-and-paste the whole class definition + * into the new module, but use only your new instantiation types. + * - When forward-declaring template instantiations, use the generated/typedefed name, e.g. + * class gtsam::Class1Pose2; + * class gtsam::MyInstantiatedClass; */ /** * Status: * - TODO: global functions * - TODO: default values for arguments - * - TODO: overloaded functions - * - TODO: signatures for constructors can be ambiguous if two types have the same first letter * - TODO: Handle gtsam::Rot3M conversions to quaternions */ @@ -64,7 +88,17 @@ namespace gtsam { // base //************************************************************************* -class LieVector { +virtual class Value { + // No constructors because this is an abstract class + + // Testable + void print(string s) const; + + // Manifold + size_t dim() const; +}; + +virtual class LieVector : gtsam::Value { // Standard constructors LieVector(); LieVector(Vector v); @@ -96,7 +130,7 @@ class LieVector { // geometry //************************************************************************* -class Point2 { +virtual class Point2 : gtsam::Value { // Standard Constructors Point2(); Point2(double x, double y); @@ -128,7 +162,7 @@ class Point2 { Vector vector() const; }; -class StereoPoint2 { +virtual class StereoPoint2 : gtsam::Value { // Standard Constructors StereoPoint2(); StereoPoint2(double uL, double uR, double v); @@ -157,7 +191,7 @@ class StereoPoint2 { Vector vector() const; }; -class Point3 { +virtual class Point3 : gtsam::Value { // Standard Constructors Point3(); Point3(double x, double y, double z); @@ -190,7 +224,7 @@ class Point3 { double z() const; }; -class Rot2 { +virtual class Rot2 : gtsam::Value { // Standard Constructors and Named Constructors Rot2(); Rot2(double theta); @@ -232,14 +266,14 @@ class Rot2 { Matrix matrix() const; }; -class Rot3 { +virtual class Rot3 : gtsam::Value { // Standard Constructors and Named Constructors Rot3(); Rot3(Matrix R); static gtsam::Rot3 Rx(double t); static gtsam::Rot3 Ry(double t); static gtsam::Rot3 Rz(double t); -// static gtsam::Rot3 RzRyRx(double x, double y, double z); // FIXME: overloaded functions don't work yet + static gtsam::Rot3 RzRyRx(double x, double y, double z); // FIXME: overloaded functions don't work yet static gtsam::Rot3 RzRyRx(Vector xyz); static gtsam::Rot3 yaw(double t); // positive yaw is to right (as in aircraft heading) static gtsam::Rot3 pitch(double t); // positive pitch is up (increasing aircraft altitude) @@ -261,7 +295,7 @@ class Rot3 { // Manifold static size_t Dim(); size_t dim() const; - // gtsam::Rot3 retractCayley(Vector v) const; // FIXME, does not exist in both Matrix and Quaternion options + gtsam::Rot3 retractCayley(Vector v) const; // FIXME, does not exist in both Matrix and Quaternion options gtsam::Rot3 retract(Vector v) const; Vector localCoordinates(const gtsam::Rot3& p) const; @@ -284,7 +318,7 @@ class Rot3 { // Vector toQuaternion() const; // FIXME: Can't cast to Vector properly }; -class Pose2 { +virtual class Pose2 : gtsam::Value { // Standard Constructor Pose2(); Pose2(double x, double y, double theta); @@ -330,12 +364,12 @@ class Pose2 { Matrix matrix() const; }; -class Pose3 { +virtual class Pose3 : gtsam::Value { // Standard Constructors Pose3(); Pose3(const gtsam::Pose3& pose); Pose3(const gtsam::Rot3& r, const gtsam::Point3& t); - // Pose3(const gtsam::Pose2& pose2); // FIXME: shadows Pose3(Pose3 pose) + Pose3(const gtsam::Pose2& pose2); // FIXME: shadows Pose3(Pose3 pose) Pose3(Matrix t); // Testable @@ -373,19 +407,20 @@ class Pose3 { double y() const; double z() const; Matrix matrix() const; - // gtsam::Pose3 transform_to(const gtsam::Pose3& pose) const; // FIXME: shadows other transform_to() + gtsam::Pose3 transform_to(const gtsam::Pose3& pose) const; // FIXME: shadows other transform_to() double range(const gtsam::Point3& point); - // double range(const gtsam::Pose3& pose); // FIXME: shadows other range + double range(const gtsam::Pose3& pose); }; -class Cal3_S2 { +virtual class Cal3_S2 : gtsam::Value { // Standard Constructors Cal3_S2(); Cal3_S2(double fx, double fy, double s, double u0, double v0); + Cal3_S2(Vector v); // Testable void print(string s) const; - bool equals(const gtsam::Cal3_S2& pose, double tol) const; + bool equals(const gtsam::Cal3_S2& rhs, double tol) const; // Manifold static size_t Dim(); @@ -409,6 +444,37 @@ class Cal3_S2 { Matrix matrix_inverse() const; }; +virtual class Cal3DS2 : gtsam::Value { + // Standard Constructors + Cal3DS2(); + Cal3DS2(double fx, double fy, double s, double u0, double v0, double k1, double k2, double k3, double k4); + Cal3DS2(Vector v); + + // Testable + void print(string s) const; + bool equals(const gtsam::Cal3DS2& rhs, double tol) const; + + // Manifold + static size_t Dim(); + size_t dim() const; + gtsam::Cal3DS2 retract(Vector v) const; + Vector localCoordinates(const gtsam::Cal3DS2& c) const; + + // Action on Point2 + gtsam::Point2 uncalibrate(const gtsam::Point2& p) const; + // TODO: D2d functions that start with an uppercase letter + + // Standard Interface + double fx() const; + double fy() const; + double skew() const; + double px() const; + double py() const; + Vector vector() const; + Vector k() const; + //Matrix K() const; //FIXME: Uppercase +}; + class Cal3_S2Stereo { // Standard Constructors Cal3_S2Stereo(); @@ -428,7 +494,7 @@ class Cal3_S2Stereo { double baseline() const; }; -class CalibratedCamera { +virtual class CalibratedCamera : gtsam::Value { // Standard Constructors and Named Constructors CalibratedCamera(); CalibratedCamera(const gtsam::Pose3& pose); @@ -458,14 +524,14 @@ class CalibratedCamera { double range(const gtsam::Point3& p) const; // TODO: Other overloaded range methods }; -class SimpleCamera { +virtual class SimpleCamera : gtsam::Value { // Standard Constructors and Named Constructors SimpleCamera(); SimpleCamera(const gtsam::Pose3& pose); SimpleCamera(const gtsam::Pose3& pose, const gtsam::Cal3_S2& K); static gtsam::SimpleCamera level(const gtsam::Cal3_S2& K, const gtsam::Pose2& pose, double height); - // static gtsam::SimpleCamera level(const gtsam::Pose2& pose, double height); // FIXME overload + static gtsam::SimpleCamera level(const gtsam::Pose2& pose, double height); // FIXME overload static gtsam::SimpleCamera lookat(const gtsam::Point3& eye, const gtsam::Point3& target, const gtsam::Point3& upVector, const gtsam::Cal3_S2& K); @@ -490,7 +556,7 @@ class SimpleCamera { gtsam::Point2 project(const gtsam::Point3& point); gtsam::Point3 backproject(const gtsam::Point2& p, double depth) const; double range(const gtsam::Point3& point); - // double range(const gtsam::Pose3& point); // FIXME, overload + double range(const gtsam::Pose3& point); // FIXME, overload }; //************************************************************************* @@ -679,17 +745,17 @@ class VariableIndex { #include namespace noiseModel { -class Base { +virtual class Base { }; -class Gaussian { +virtual class Gaussian : gtsam::noiseModel::Base { static gtsam::noiseModel::Gaussian* SqrtInformation(Matrix R); static gtsam::noiseModel::Gaussian* Covariance(Matrix R); // Matrix R() const; // FIXME: cannot parse!!! void print(string s) const; }; -class Diagonal { +virtual class Diagonal : gtsam::noiseModel::Gaussian { static gtsam::noiseModel::Diagonal* Sigmas(Vector sigmas); static gtsam::noiseModel::Diagonal* Variances(Vector variances); static gtsam::noiseModel::Diagonal* Precisions(Vector precisions); @@ -697,14 +763,14 @@ class Diagonal { void print(string s) const; }; -class Isotropic { +virtual class Isotropic : gtsam::noiseModel::Diagonal { static gtsam::noiseModel::Isotropic* Sigma(size_t dim, double sigma); static gtsam::noiseModel::Isotropic* Variance(size_t dim, double varianace); static gtsam::noiseModel::Isotropic* Precision(size_t dim, double precision); void print(string s) const; }; -class Unit { +virtual class Unit : gtsam::noiseModel::Isotropic { static gtsam::noiseModel::Unit* Create(size_t dim); void print(string s) const; }; @@ -759,7 +825,7 @@ class GaussianBayesNet { void push_front(gtsam::GaussianConditional* conditional); }; -class GaussianFactor { +virtual class GaussianFactor { void print(string s) const; bool equals(const gtsam::GaussianFactor& lf, double tol) const; double error(const gtsam::VectorValues& c) const; @@ -767,7 +833,7 @@ class GaussianFactor { size_t size() const; }; -class JacobianFactor { +virtual class JacobianFactor : gtsam::GaussianFactor { JacobianFactor(); JacobianFactor(Vector b_in); JacobianFactor(size_t i1, Matrix A1, Vector b, @@ -787,7 +853,7 @@ class JacobianFactor { gtsam::GaussianFactor* negate() const; }; -class HessianFactor { +virtual class HessianFactor : gtsam::GaussianFactor { HessianFactor(const gtsam::HessianFactor& gf); HessianFactor(); HessianFactor(size_t j, Matrix G, Vector g, double f); @@ -811,22 +877,19 @@ class GaussianFactorGraph { GaussianFactorGraph(const gtsam::GaussianBayesNet& CBN); // From FactorGraph - void push_back(gtsam::GaussianFactor* factor); void print(string s) const; bool equals(const gtsam::GaussianFactorGraph& lfgraph, double tol) const; size_t size() const; gtsam::GaussianFactor* at(size_t idx) const; // Building the graph - void add(gtsam::JacobianFactor* factor); - // all these won't work as MATLAB can't handle overloading -// void add(Vector b); -// void add(size_t key1, Matrix A1, Vector b, const gtsam::SharedDiagonal& model); -// void add(size_t key1, Matrix A1, size_t key2, Matrix A2, Vector b, -// const gtsam::SharedDiagonal& model); -// void add(size_t key1, Matrix A1, size_t key2, Matrix A2, size_t key3, Matrix A3, -// Vector b, const gtsam::SharedDiagonal& model); -// void add(gtsam::HessianFactor* factor); + void push_back(gtsam::GaussianFactor* factor); + void add(Vector b); + void add(size_t key1, Matrix A1, Vector b, const gtsam::noiseModel::Diagonal* model); + void add(size_t key1, Matrix A1, size_t key2, Matrix A2, Vector b, + const gtsam::noiseModel::Diagonal* model); + void add(size_t key1, Matrix A1, size_t key2, Matrix A2, size_t key3, Matrix A3, + Vector b, const gtsam::noiseModel::Diagonal* model); // error and probability double error(const gtsam::VectorValues& c) const; @@ -909,29 +972,55 @@ class Ordering { void insert(size_t key, size_t order); void push_back(size_t key); void permuteWithInverse(const gtsam::Permutation& inversePermutation); - // FIXME: Wrap InvertedMap as well - //InvertedMap invert() const; + gtsam::InvertedOrdering invert() const; +}; + +#include +class InvertedOrdering { + InvertedOrdering(); + + // FIXME: add bracket operator overload + + bool empty() const; + size_t size() const; + bool count(size_t index) const; // Use as a boolean function with implicit cast + + void clear(); }; class NonlinearFactorGraph { NonlinearFactorGraph(); void print(string s) const; + double error(const gtsam::Values& c) const; + double probPrime(const gtsam::Values& c) const; + gtsam::NonlinearFactor* at(size_t i) const; + void add(const gtsam::NonlinearFactor* factor); + gtsam::Ordering* orderingCOLAMD(const gtsam::Values& c) const; + // Ordering* orderingCOLAMDConstrained(const gtsam::Values& c, const std::map& constraints) const; + gtsam::GaussianFactorGraph* linearize(const gtsam::Values& c, const gtsam::Ordering& ordering) const; + gtsam::NonlinearFactorGraph clone() const; }; -class NonlinearFactor { -// NonlinearFactor(); // FIXME: don't use this - creates an abstract class +virtual class NonlinearFactor { void print(string s) const; void equals(const gtsam::NonlinearFactor& other, double tol) const; gtsam::KeyVector keys() const; size_t size() const; - size_t dim() const; // FIXME: Doesn't link + size_t dim() const; + double error(const gtsam::Values& c) const; + bool active(const gtsam::Values& c) const; + gtsam::GaussianFactor* linearize(const gtsam::Values& c, const gtsam::Ordering& ordering) const; + gtsam::NonlinearFactor* clone() const; + // gtsam::NonlinearFactor* rekey(const gtsam::KeyVector& newKeys) const; //FIXME: Conversion from KeyVector to std::vector does not happen }; class Values { Values(); size_t size() const; void print(string s) const; + void insert(size_t j, const gtsam::Value& value); bool exists(size_t j) const; + gtsam::Value at(size_t j) const; }; // Actually a FastList @@ -1012,13 +1101,13 @@ class LevenbergMarquardtParams { LevenbergMarquardtParams(); void print(string s) const; - double getMaxIterations() const; + size_t getMaxIterations() const; double getRelativeErrorTol() const; double getAbsoluteErrorTol() const; double getErrorTol() const; string getVerbosity() const; - void setMaxIterations(double value); + void setMaxIterations(size_t value); void setRelativeErrorTol(double value); void setAbsoluteErrorTol(double value); void setErrorTol(double value); @@ -1040,6 +1129,59 @@ class LevenbergMarquardtParams { void setVerbosityLM(string s); }; +//************************************************************************* +// Nonlinear factor types +//************************************************************************* +template +virtual class PriorFactor : gtsam::NonlinearFactor { + PriorFactor(size_t key, const T& prior, const gtsam::noiseModel::Base* noiseModel); +}; + + +template +virtual class BetweenFactor : gtsam::NonlinearFactor { + BetweenFactor(size_t key1, size_t key2, const T& relativePose, const gtsam::noiseModel::Base* noiseModel); +}; + + +template +virtual class NonlinearEquality : gtsam::NonlinearFactor { + // Constructor - forces exact evaluation + NonlinearEquality(size_t j, const T& feasible); + // Constructor - allows inexact evaluation + NonlinearEquality(size_t j, const T& feasible, double error_gain); +}; + + +template +virtual class RangeFactor : gtsam::NonlinearFactor { + RangeFactor(size_t key1, size_t key2, double measured, const gtsam::noiseModel::Base* noiseModel); +}; + +typedef gtsam::RangeFactor RangeFactor2D; +typedef gtsam::RangeFactor RangeFactor3D; +typedef gtsam::RangeFactor RangeFactorCalibratedCamera; +typedef gtsam::RangeFactor RangeFactorSimpleCamera; + +template +virtual class BearingFactor : gtsam::NonlinearFactor { + BearingFactor(size_t key1, size_t key2, const ROT& measured, const gtsam::noiseModel::Base* noiseModel); +}; + +typedef gtsam::BearingFactor BearingFactor2D; + + +#include +template +virtual class GenericProjectionFactor : gtsam::NonlinearFactor { + GenericProjectionFactor(const gtsam::Point2& measured, const gtsam::noiseModel::Base* noiseModel, + size_t poseKey, size_t pointKey, const CALIBRATION* k); + gtsam::Point2 measured() const; + CALIBRATION* calibration() const; +}; +typedef gtsam::GenericProjectionFactor GenericProjectionFactorCal3_S2; +typedef gtsam::GenericProjectionFactor GenericProjectionFactorCal3DS2; + }///\namespace gtsam //************************************************************************* diff --git a/gtsam/CMakeLists.txt b/gtsam/CMakeLists.txt index fb732ca51..66870a09c 100644 --- a/gtsam/CMakeLists.txt +++ b/gtsam/CMakeLists.txt @@ -95,9 +95,6 @@ if (GTSAM_BUILD_STATIC_LIBRARY) list(APPEND GTSAM_EXPORTED_TARGETS gtsam-static) set(GTSAM_EXPORTED_TARGETS "${GTSAM_EXPORTED_TARGETS}" PARENT_SCOPE) set(gtsam-lib gtsam-static) - if(NOT GTSAM_BUILD_SHARED_LIBRARY) - set(gtsam-prefer-shared gtsam-static) - endif() endif (GTSAM_BUILD_STATIC_LIBRARY) if (GTSAM_BUILD_SHARED_LIBRARY) @@ -115,34 +112,23 @@ if (GTSAM_BUILD_SHARED_LIBRARY) if (NOT GTSAM_BUILD_STATIC_LIBRARY) set(gtsam-lib "gtsam-shared") endif() - set(gtsam-prefer-shared gtsam-shared) endif(GTSAM_BUILD_SHARED_LIBRARY) # Create the matlab toolbox for the gtsam library -if (GTSAM_BUILD_WRAP) +if (GTSAM_INSTALL_MATLAB_TOOLBOX) # Set up codegen include(GtsamMatlabWrap) # TODO: generate these includes programmatically # Choose include flags depending on build process - if (GTSAM_BUILD_MEX_BIN) - set(MEX_INCLUDE_ROOT ${GTSAM_SOURCE_ROOT_DIR}) - set(MEX_LIB_ROOT ${CMAKE_BINARY_DIR}) - set(GTSAM_LIB_DIR ${MEX_LIB_ROOT}/gtsam) - else() - set(MEX_INCLUDE_ROOT ${CMAKE_INSTALL_PREFIX}/include) - set(MEX_LIB_ROOT ${CMAKE_INSTALL_PREFIX}/lib) - set(GTSAM_LIB_DIR ${MEX_LIB_ROOT}) - endif() + set(MEX_INCLUDE_ROOT ${GTSAM_SOURCE_ROOT_DIR}) + set(MEX_LIB_ROOT ${CMAKE_BINARY_DIR}) + set(GTSAM_LIB_DIR ${MEX_LIB_ROOT}/gtsam) # Generate, build and install toolbox - string(TOUPPER ${CMAKE_BUILD_TYPE} build_type_toupper) - get_target_property(gtsam_library_file ${gtsam-prefer-shared} LOCATION_${build_type_toupper}) - set(mexFlags "${GTSAM_BUILD_MEX_BINARY_FLAGS} -I${Boost_INCLUDE_DIR} -I${MEX_INCLUDE_ROOT} -I${MEX_INCLUDE_ROOT}/gtsam -I${MEX_INCLUDE_ROOT}/gtsam/base -I${MEX_INCLUDE_ROOT}/gtsam/geometry -I${MEX_INCLUDE_ROOT}/gtsam/linear -I${MEX_INCLUDE_ROOT}/gtsam/discrete -I${MEX_INCLUDE_ROOT}/gtsam/inference -I${MEX_INCLUDE_ROOT}/gtsam/nonlinear -I${MEX_INCLUDE_ROOT}/gtsam/slam ${gtsam_library_file}") - # Lots of escapes '\' here because they get eaten during subsequent calls to 'set' - set(mexFlags "${mexFlags} -g COMPFLAGS=\\\"$$COMPFLAGS ${CMAKE_CXX_FLAGS} ${CMAKE_CXX_FLAGS_${build_type_toupper}}\\\"") + set(mexFlags ${GTSAM_BUILD_MEX_BINARY_FLAGS} -I${Boost_INCLUDE_DIR} -I${MEX_INCLUDE_ROOT} -I${MEX_INCLUDE_ROOT}/gtsam -I${MEX_INCLUDE_ROOT}/gtsam/base -I${MEX_INCLUDE_ROOT}/gtsam/geometry -I${MEX_INCLUDE_ROOT}/gtsam/linear -I${MEX_INCLUDE_ROOT}/gtsam/discrete -I${MEX_INCLUDE_ROOT}/gtsam/inference -I${MEX_INCLUDE_ROOT}/gtsam/nonlinear -I${MEX_INCLUDE_ROOT}/gtsam/slam) # Macro to handle details of setting up targets # FIXME: issue with dependency between wrap_gtsam and wrap_gtsam_build, only shows up on CMake 2.8.3 - wrap_library(gtsam "${mexFlags}" "../") + wrap_library(gtsam "${mexFlags}" "../" "") endif () diff --git a/gtsam/base/DerivedValue.h b/gtsam/base/DerivedValue.h index 6c10a29f5..4f6dae9c7 100644 --- a/gtsam/base/DerivedValue.h +++ b/gtsam/base/DerivedValue.h @@ -16,7 +16,7 @@ */ #pragma once - +#include #include #include @@ -37,7 +37,8 @@ public: /** * Create a duplicate object returned as a pointer to the generic Value interface. - * For the sake of performance, this function use singleton pool allocator instead of the normal heap allocator + * For the sake of performance, this function use singleton pool allocator instead of the normal heap allocator. + * The result must be deleted with Value::deallocate_, not with the 'delete' operator. */ virtual Value* clone_() const { void *place = boost::singleton_pool::malloc(); @@ -53,6 +54,13 @@ public: boost::singleton_pool::free((void*)this); } + /** + * Clone this value (normal clone on the heap, delete with 'delete' operator) + */ + virtual boost::shared_ptr clone() const { + return boost::make_shared(static_cast(*this)); + } + /// equals implementing generic Value interface virtual bool equals_(const Value& p, double tol = 1e-9) const { // Cast the base class Value pointer to a derived class pointer diff --git a/gtsam/base/Value.h b/gtsam/base/Value.h index 394a11e72..8b19a6532 100644 --- a/gtsam/base/Value.h +++ b/gtsam/base/Value.h @@ -101,12 +101,15 @@ namespace gtsam { class Value { public: - /** Allocate and construct a clone of this value */ + /** Clone this value in a special memory pool, must be deleted with Value::deallocate_, *not* with the 'delete' operator. */ virtual Value* clone_() const = 0; /** Deallocate a raw pointer of this value */ virtual void deallocate_() const = 0; + /** Clone this value (normal clone on the heap, delete with 'delete' operator) */ + virtual boost::shared_ptr clone() const = 0; + /** Compare this Value with another for equality. */ virtual bool equals_(const Value& other, double tol = 1e-9) const = 0; diff --git a/gtsam/linear/GaussianFactorGraph.h b/gtsam/linear/GaussianFactorGraph.h index b4878565e..fd1ec1f6c 100644 --- a/gtsam/linear/GaussianFactorGraph.h +++ b/gtsam/linear/GaussianFactorGraph.h @@ -83,32 +83,32 @@ namespace gtsam { push_back(fg); } - /** Add a Jacobian factor */ - void add(const boost::shared_ptr& factor) { - factors_.push_back(boost::shared_ptr(factor)); + /** Add a factor by value - makes a copy */ + void add(const GaussianFactor& factor) { + factors_.push_back(factor.clone()); } - /** Add a Hessian factor */ - void add(const boost::shared_ptr& factor) { - factors_.push_back(boost::shared_ptr(factor)); + /** Add a factor by pointer - stores pointer without copying the factor */ + void add(const sharedFactor& factor) { + factors_.push_back(factor); } /** Add a null factor */ void add(const Vector& b) { - add(JacobianFactor::shared_ptr(new JacobianFactor(b))); + add(JacobianFactor(b)); } /** Add a unary factor */ void add(Index key1, const Matrix& A1, const Vector& b, const SharedDiagonal& model) { - add(JacobianFactor::shared_ptr(new JacobianFactor(key1,A1,b,model))); + add(JacobianFactor(key1,A1,b,model)); } /** Add a binary factor */ void add(Index key1, const Matrix& A1, Index key2, const Matrix& A2, const Vector& b, const SharedDiagonal& model) { - add(JacobianFactor::shared_ptr(new JacobianFactor(key1,A1,key2,A2,b,model))); + add(JacobianFactor(key1,A1,key2,A2,b,model)); } /** Add a ternary factor */ @@ -116,13 +116,13 @@ namespace gtsam { Index key2, const Matrix& A2, Index key3, const Matrix& A3, const Vector& b, const SharedDiagonal& model) { - add(JacobianFactor::shared_ptr(new JacobianFactor(key1,A1,key2,A2,key3,A3,b,model))); + add(JacobianFactor(key1,A1,key2,A2,key3,A3,b,model)); } /** Add an n-ary factor */ void add(const std::vector > &terms, const Vector &b, const SharedDiagonal& model) { - add(JacobianFactor::shared_ptr(new JacobianFactor(terms,b,model))); + add(JacobianFactor(terms,b,model)); } /** diff --git a/gtsam/linear/KalmanFilter.h b/gtsam/linear/KalmanFilter.h index aeec47a39..df4cd1d65 100644 --- a/gtsam/linear/KalmanFilter.h +++ b/gtsam/linear/KalmanFilter.h @@ -17,6 +17,8 @@ * @author Frank Dellaert */ +#pragma once + #include #include diff --git a/gtsam/linear/VectorValues.h b/gtsam/linear/VectorValues.h index aa9c1aa6d..9fad99223 100644 --- a/gtsam/linear/VectorValues.h +++ b/gtsam/linear/VectorValues.h @@ -419,7 +419,7 @@ namespace gtsam { maps_.reserve(maps_.size() + dimensions.size()); BOOST_FOREACH(size_t dim, dimensions) { maps_.push_back(values_.segment(varStart, dim)); - varStart += dim; // varStart is continued from first for loop + varStart += (int)dim; // varStart is continued from first for loop } } diff --git a/gtsam/nonlinear/NonlinearFactorGraph.h b/gtsam/nonlinear/NonlinearFactorGraph.h index 85cc0e63f..f7ebb42bc 100644 --- a/gtsam/nonlinear/NonlinearFactorGraph.h +++ b/gtsam/nonlinear/NonlinearFactorGraph.h @@ -55,9 +55,14 @@ namespace gtsam { /** Unnormalized probability. O(n) */ double probPrime(const Values& c) const; - template - void add(const F& factor) { - this->push_back(boost::shared_ptr(new F(factor))); + /// Add a factor by value - copies the factor object + void add(const NonlinearFactor& factor) { + this->push_back(factor.clone()); + } + + /// Add a factor by pointer - stores pointer without copying factor object + void add(const sharedFactor& factor) { + this->push_back(factor); } /** diff --git a/gtsam/nonlinear/NonlinearOptimizer.h b/gtsam/nonlinear/NonlinearOptimizer.h index 44b352938..1c071faef 100644 --- a/gtsam/nonlinear/NonlinearOptimizer.h +++ b/gtsam/nonlinear/NonlinearOptimizer.h @@ -45,23 +45,23 @@ public: Verbosity verbosity; ///< The printing verbosity during optimization (default SILENT) NonlinearOptimizerParams() : - maxIterations(100.0), relativeErrorTol(1e-5), absoluteErrorTol(1e-5), + maxIterations(100), relativeErrorTol(1e-5), absoluteErrorTol(1e-5), errorTol(0.0), verbosity(SILENT) {} virtual ~NonlinearOptimizerParams() {} virtual void print(const std::string& str = "") const ; - inline double getMaxIterations() const { return maxIterations; } - inline double getRelativeErrorTol() const { return relativeErrorTol; } - inline double getAbsoluteErrorTol() const { return absoluteErrorTol; } - inline double getErrorTol() const { return errorTol; } - inline std::string getVerbosity() const { return verbosityTranslator(verbosity); } + size_t getMaxIterations() const { return maxIterations; } + double getRelativeErrorTol() const { return relativeErrorTol; } + double getAbsoluteErrorTol() const { return absoluteErrorTol; } + double getErrorTol() const { return errorTol; } + std::string getVerbosity() const { return verbosityTranslator(verbosity); } - inline void setMaxIterations(double value) { maxIterations = value; } - inline void setRelativeErrorTol(double value) { relativeErrorTol = value; } - inline void setAbsoluteErrorTol(double value) { absoluteErrorTol = value; } - inline void setErrorTol(double value) { errorTol = value ; } - inline void setVerbosity(const std::string &src) { verbosity = verbosityTranslator(src); } + void setMaxIterations(size_t value) { maxIterations = value; } + void setRelativeErrorTol(double value) { relativeErrorTol = value; } + void setAbsoluteErrorTol(double value) { absoluteErrorTol = value; } + void setErrorTol(double value) { errorTol = value ; } + void setVerbosity(const std::string &src) { verbosity = verbosityTranslator(src); } Verbosity verbosityTranslator(const std::string &s) const; std::string verbosityTranslator(Verbosity value) const; diff --git a/gtsam/nonlinear/Ordering.h b/gtsam/nonlinear/Ordering.h index 098976a36..c6881fbde 100644 --- a/gtsam/nonlinear/Ordering.h +++ b/gtsam/nonlinear/Ordering.h @@ -155,7 +155,7 @@ public: iterator end() { return order_.end(); } /// Test if the key exists in the ordering. - bool exists(Key key) const { return order_.count(key); } + bool exists(Key key) const { return order_.count(key) > 0; } ///TODO: comment std::pair tryInsert(Key key, Index order) { return tryInsert(std::make_pair(key,order)); } @@ -233,7 +233,10 @@ private: ar & BOOST_SERIALIZATION_NVP(order_); ar & BOOST_SERIALIZATION_NVP(nVars_); } -}; +}; // \class Ordering + +// typedef for use with matlab +typedef Ordering::InvertedMap InvertedOrdering; /** * @class Unordered diff --git a/gtsam/slam/BearingFactor.h b/gtsam/slam/BearingFactor.h index c42c2798d..62e46d53e 100644 --- a/gtsam/slam/BearingFactor.h +++ b/gtsam/slam/BearingFactor.h @@ -25,12 +25,12 @@ namespace gtsam { /** * Binary factor for a bearing measurement */ - template + template class BearingFactor: public NoiseModelFactor2 { private: typedef POSE Pose; - typedef typename Pose::Rotation Rot; + typedef ROT Rot; typedef POINT Point; typedef BearingFactor This; diff --git a/gtsam/slam/ProjectionFactor.h b/gtsam/slam/ProjectionFactor.h index bce7bcf84..048756435 100644 --- a/gtsam/slam/ProjectionFactor.h +++ b/gtsam/slam/ProjectionFactor.h @@ -62,7 +62,7 @@ namespace gtsam { * @param K shared pointer to the constant calibration */ GenericProjectionFactor(const Point2& measured, const SharedNoiseModel& model, - const Key poseKey, Key pointKey, const shared_ptrK& K) : + Key poseKey, Key pointKey, const boost::shared_ptr& K) : Base(model, poseKey, pointKey), measured_(measured), K_(K) { } diff --git a/gtsam_unstable/CMakeLists.txt b/gtsam_unstable/CMakeLists.txt index acd36ddc2..09fb124a9 100644 --- a/gtsam_unstable/CMakeLists.txt +++ b/gtsam_unstable/CMakeLists.txt @@ -15,10 +15,12 @@ add_custom_target(check.unstable COMMAND ${CMAKE_CTEST_COMMAND} --output-on-fail foreach(subdir ${gtsam_unstable_subdirs}) # Build convenience libraries file(GLOB subdir_srcs "${subdir}/*.cpp") - set(${subdir}_srcs ${subdir_srcs}) + file(GLOB subdir_headers "${subdir}/*.h") + set(${subdir}_srcs ${subdir_srcs} ${subdir_headers}) + gtsam_assign_source_folders("${${subdir}_srcs}") # Create MSVC structure if (subdir_srcs AND GTSAM_BUILD_CONVENIENCE_LIBRARIES) message(STATUS "Building Convenience Library: ${subdir}_unstable") - add_library("${subdir}_unstable" STATIC ${subdir_srcs}) + add_library("${subdir}_unstable" STATIC ${${subdir}_srcs}) endif() # Build local library and tests @@ -36,7 +38,9 @@ set(gtsam_unstable_srcs ${slam_srcs} ) -option (GTSAM_UNSTABLE_BUILD_SHARED_LIBRARY "Enable/Disable building of a shared version of gtsam_unstable" ON) +if(NOT MSVC) + option (GTSAM_UNSTABLE_BUILD_SHARED_LIBRARY "Enable/Disable building of a shared version of gtsam_unstable" ON) +endif() # Versions - same as core gtsam library set(gtsam_unstable_version ${GTSAM_VERSION_MAJOR}.${GTSAM_VERSION_MINOR}.${GTSAM_VERSION_PATCH}) @@ -73,28 +77,21 @@ if (GTSAM_UNSTABLE_BUILD_SHARED_LIBRARY) endif(GTSAM_UNSTABLE_BUILD_SHARED_LIBRARY) # Wrap version for gtsam_unstable -if (GTSAM_BUILD_WRAP) +if (GTSAM_INSTALL_MATLAB_TOOLBOX) # Set up codegen include(GtsamMatlabWrap) # TODO: generate these includes programmatically # Choose include flags depending on build process - if (GTSAM_BUILD_MEX_BIN) - set(MEX_INCLUDE_ROOT ${GTSAM_SOURCE_ROOT_DIR}) - set(MEX_LIB_ROOT ${CMAKE_BINARY_DIR}) - set(GTSAM_LIB_DIR ${MEX_LIB_ROOT}/gtsam) - set(GTSAM_UNSTABLE_LIB_DIR ${MEX_LIB_ROOT}/gtsam_unstable) - else() - set(MEX_INCLUDE_ROOT ${CMAKE_INSTALL_PREFIX}/include) - set(MEX_LIB_ROOT ${CMAKE_INSTALL_PREFIX}/lib) - set(GTSAM_LIB_DIR ${MEX_LIB_ROOT}) - set(GTSAM_UNSTABLE_LIB_DIR ${MEX_LIB_ROOT}) - endif() + set(MEX_INCLUDE_ROOT ${GTSAM_SOURCE_ROOT_DIR}) + set(MEX_LIB_ROOT ${CMAKE_BINARY_DIR}) + set(GTSAM_LIB_DIR ${MEX_LIB_ROOT}/gtsam) + set(GTSAM_UNSTABLE_LIB_DIR ${MEX_LIB_ROOT}/gtsam_unstable) # Generate, build and install toolbox - set(mexFlags "-I${Boost_INCLUDE_DIR} -I${MEX_INCLUDE_ROOT} -I${MEX_INCLUDE_ROOT}/gtsam_unstable -I${MEX_INCLUDE_ROOT}/gtsam_unstable/dynamics -I${MEX_INCLUDE_ROOT}/gtsam_unstable/discrete -L${GTSAM_UNSTABLE_LIB_DIR} -L${GTSAM_LIB_DIR} -lgtsam -lgtsam_unstable") + set(mexFlags -I${Boost_INCLUDE_DIR} -I${MEX_INCLUDE_ROOT} -I${MEX_INCLUDE_ROOT}/gtsam_unstable -I${MEX_INCLUDE_ROOT}/gtsam_unstable/dynamics -I${MEX_INCLUDE_ROOT}/gtsam_unstable/discrete) # Macro to handle details of setting up targets - wrap_library(gtsam_unstable "${mexFlags}" "./") + wrap_library(gtsam_unstable "${mexFlags}" "./" gtsam) -endif(GTSAM_BUILD_WRAP) +endif(GTSAM_INSTALL_MATLAB_TOOLBOX) diff --git a/gtsam_unstable/dynamics/FullIMUFactor.h b/gtsam_unstable/dynamics/FullIMUFactor.h index c9a75ec23..f42ecc352 100644 --- a/gtsam_unstable/dynamics/FullIMUFactor.h +++ b/gtsam_unstable/dynamics/FullIMUFactor.h @@ -77,8 +77,6 @@ public: const Vector& gyro() const { return gyro_; } const Vector& accel() const { return accel_; } Vector z() const { return concatVectors(2, &accel_, &gyro_); } - const Key& key1() const { return this->key1_; } - const Key& key2() const { return this->key2_; } /** * Error evaluation with optional derivatives - calculates diff --git a/gtsam_unstable/dynamics/IMUFactor.h b/gtsam_unstable/dynamics/IMUFactor.h index adcf772e3..9e5651cc9 100644 --- a/gtsam_unstable/dynamics/IMUFactor.h +++ b/gtsam_unstable/dynamics/IMUFactor.h @@ -70,8 +70,6 @@ public: const Vector& gyro() const { return gyro_; } const Vector& accel() const { return accel_; } Vector z() const { return concatVectors(2, &accel_, &gyro_); } - const Key& key1() const { return this->key1_; } - const Key& key2() const { return this->key2_; } /** * Error evaluation with optional derivatives - calculates diff --git a/gtsam_unstable/gtsam_unstable.h b/gtsam_unstable/gtsam_unstable.h index c9d114d58..3d9fd7aac 100644 --- a/gtsam_unstable/gtsam_unstable.h +++ b/gtsam_unstable/gtsam_unstable.h @@ -3,10 +3,12 @@ */ // specify the classes from gtsam we are using -class gtsam::Point3; -class gtsam::Rot3; -class gtsam::Pose3; -class gtsam::SharedNoiseModel; +virtual class gtsam::Value; +virtual class gtsam::Point3; +virtual class gtsam::Rot3; +virtual class gtsam::Pose3; +virtual class gtsam::noiseModel::Base; +virtual class gtsam::NonlinearFactor; namespace gtsam { @@ -18,7 +20,7 @@ class Dummy { }; #include -class PoseRTV { +virtual class PoseRTV : gtsam::Value { PoseRTV(); PoseRTV(Vector rtv); PoseRTV(const gtsam::Point3& pt, const gtsam::Rot3& rot, const gtsam::Point3& vel); @@ -66,6 +68,107 @@ class PoseRTV { Vector translationIntegrationVec(const gtsam::PoseRTV& x2, double dt) const; }; + +// Nonlinear factors from gtsam, for our Value types +#include +template +virtual class PriorFactor : gtsam::NonlinearFactor { + PriorFactor(size_t key, const T& prior, const gtsam::noiseModel::Base* noiseModel); +}; + + +#include +template +virtual class BetweenFactor : gtsam::NonlinearFactor { + BetweenFactor(size_t key1, size_t key2, const T& relativePose, const gtsam::noiseModel::Base* noiseModel); +}; + + +#include +template +virtual class RangeFactor : gtsam::NonlinearFactor { + RangeFactor(size_t key1, size_t key2, double measured, const gtsam::noiseModel::Base* noiseModel); +}; + +typedef gtsam::RangeFactor RangeFactorRTV; + + +#include +template +virtual class NonlinearEquality : gtsam::NonlinearFactor { + // Constructor - forces exact evaluation + NonlinearEquality(size_t j, const T& feasible); + // Constructor - allows inexact evaluation + NonlinearEquality(size_t j, const T& feasible, double error_gain); +}; + + +template +virtual class IMUFactor : gtsam::NonlinearFactor { + /** Standard constructor */ + IMUFactor(Vector accel, Vector gyro, + double dt, size_t key1, size_t key2, const gtsam::noiseModel::Base* model); + + /** Full IMU vector specification */ + IMUFactor(Vector imu_vector, + double dt, size_t key1, size_t key2, const gtsam::noiseModel::Base* model); + + Vector gyro() const; + Vector accel() const; + Vector z() const; + size_t key1() const; + size_t key2() const; +}; + + +template +virtual class FullIMUFactor : gtsam::NonlinearFactor { + /** Standard constructor */ + FullIMUFactor(Vector accel, Vector gyro, + double dt, size_t key1, size_t key2, const gtsam::noiseModel::Base* model); + + /** Single IMU vector - imu = [accel, gyro] */ + FullIMUFactor(Vector imu, + double dt, size_t key1, size_t key2, const gtsam::noiseModel::Base* model); + + Vector gyro() const; + Vector accel() const; + Vector z() const; + size_t key1() const; + size_t key2() const; +}; + + +#include +virtual class DHeightPrior : gtsam::NonlinearFactor { + DHeightPrior(size_t key, double height, const gtsam::noiseModel::Base* model); +}; + + +#include +virtual class DRollPrior : gtsam::NonlinearFactor { + /** allows for explicit roll parameterization - uses canonical coordinate */ + DRollPrior(size_t key, double wx, const gtsam::noiseModel::Base* model); + /** Forces roll to zero */ + DRollPrior(size_t key, const gtsam::noiseModel::Base* model); +}; + + +#include +virtual class VelocityPrior : gtsam::NonlinearFactor { + VelocityPrior(size_t key, Vector vel, const gtsam::noiseModel::Base* model); +}; + + +#include +virtual class DGroundConstraint : gtsam::NonlinearFactor { + // Primary constructor allows for variable height of the "floor" + DGroundConstraint(size_t key, double height, const gtsam::noiseModel::Base* model); + // Fully specify vector - use only for debugging + DGroundConstraint(size_t key, Vector constraint, const gtsam::noiseModel::Base* model); +}; + + }///\namespace gtsam #include @@ -84,18 +187,18 @@ class Graph { void print(string s) const; // prior factors - void addPrior(size_t key, const gtsam::PoseRTV& pose, const gtsam::SharedNoiseModel& noiseModel); + void addPrior(size_t key, const gtsam::PoseRTV& pose, const gtsam::noiseModel::Base* noiseModel); void addConstraint(size_t key, const gtsam::PoseRTV& pose); - void addHeightPrior(size_t key, double z, const gtsam::SharedNoiseModel& noiseModel); + void addHeightPrior(size_t key, double z, const gtsam::noiseModel::Base* noiseModel); // inertial factors - void addFullIMUMeasurement(size_t key1, size_t key2, const Vector& accel, const Vector& gyro, double dt, const gtsam::SharedNoiseModel& noiseModel); - void addIMUMeasurement(size_t key1, size_t key2, const Vector& accel, const Vector& gyro, double dt, const gtsam::SharedNoiseModel& noiseModel); - void addVelocityConstraint(size_t key1, size_t key2, double dt, const gtsam::SharedNoiseModel& noiseModel); + void addFullIMUMeasurement(size_t key1, size_t key2, const Vector& accel, const Vector& gyro, double dt, const gtsam::noiseModel::Base* noiseModel); + void addIMUMeasurement(size_t key1, size_t key2, const Vector& accel, const Vector& gyro, double dt, const gtsam::noiseModel::Base* noiseModel); + void addVelocityConstraint(size_t key1, size_t key2, double dt, const gtsam::noiseModel::Base* noiseModel); // other measurements - void addBetween(size_t key1, size_t key2, const gtsam::PoseRTV& z, const gtsam::SharedNoiseModel& noiseModel); - void addRange(size_t key1, size_t key2, double z, const gtsam::SharedNoiseModel& noiseModel); + void addBetween(size_t key1, size_t key2, const gtsam::PoseRTV& z, const gtsam::noiseModel::Base* noiseModel); + void addRange(size_t key1, size_t key2, double z, const gtsam::noiseModel::Base* noiseModel); // optimization imu::Values optimize(const imu::Values& init) const; diff --git a/matlab/CMakeLists.txt b/matlab/CMakeLists.txt index 9d48a949f..84df4055c 100644 --- a/matlab/CMakeLists.txt +++ b/matlab/CMakeLists.txt @@ -1,37 +1,29 @@ # Install matlab components -if (GTSAM_BUILD_WRAP) - if (GTSAM_INSTALL_MATLAB_TOOLBOX) - # Utility functions - message(STATUS "Installing Matlab Utility Functions") - # Matlab files: *.m and *.fig - file(GLOB matlab_utils_m "${GTSAM_SOURCE_ROOT_DIR}/matlab/*.m") - file(GLOB matlab_utils_fig "${GTSAM_SOURCE_ROOT_DIR}/matlab/*.fig") - set(matlab_utils ${matlab_utils_m} ${matlab_utils_fig}) - install(FILES ${matlab_utils} DESTINATION ${GTSAM_TOOLBOX_INSTALL_PATH}/gtsam) - - # Tests - if (GTSAM_INSTALL_MATLAB_TESTS) - message(STATUS "Installing Matlab Toolbox Tests") - file(GLOB matlab_tests "${GTSAM_SOURCE_ROOT_DIR}/matlab/tests/*.m") - install(FILES ${matlab_tests} DESTINATION ${GTSAM_TOOLBOX_INSTALL_PATH}/gtsam/tests) - endif () - - # Examples - if (GTSAM_INSTALL_MATLAB_EXAMPLES) - message(STATUS "Installing Matlab Toolbox Examples") - # Matlab files: *.m and *.fig - file(GLOB matlab_examples_m "${GTSAM_SOURCE_ROOT_DIR}/matlab/examples/*.m") - file(GLOB matlab_examples_fig "${GTSAM_SOURCE_ROOT_DIR}/matlab/examples/*.fig") - set(matlab_examples ${matlab_examples_m} ${matlab_examples_fig}) - install(FILES ${matlab_examples} DESTINATION ${GTSAM_TOOLBOX_INSTALL_PATH}/gtsam/examples) - - message(STATUS "Installing Matlab Toolbox Examples (Data)") - # Data files: *.graph and *.txt - file(GLOB matlab_examples_data_graph "${GTSAM_SOURCE_ROOT_DIR}/examples/Data/*.graph") - file(GLOB matlab_examples_data_txt "${GTSAM_SOURCE_ROOT_DIR}/examples/Data/*.txt") - set(matlab_examples_data ${matlab_examples_data_graph} ${matlab_examples_data_txt}) - install(FILES ${matlab_examples_data} DESTINATION ${GTSAM_TOOLBOX_INSTALL_PATH}/gtsam/Data) - endif () - endif () -endif () +# Utility functions +message(STATUS "Installing Matlab Utility Functions") +# Matlab files: *.m and *.fig +file(GLOB matlab_utils_m "${GTSAM_SOURCE_ROOT_DIR}/matlab/*.m") +file(GLOB matlab_utils_fig "${GTSAM_SOURCE_ROOT_DIR}/matlab/*.fig") +set(matlab_utils ${matlab_utils_m} ${matlab_utils_fig}) +install(FILES ${matlab_utils} DESTINATION ${GTSAM_TOOLBOX_INSTALL_PATH}/gtsam) + +# Tests +message(STATUS "Installing Matlab Toolbox Tests") +file(GLOB matlab_tests "${GTSAM_SOURCE_ROOT_DIR}/matlab/tests/*.m") +install(FILES ${matlab_tests} DESTINATION ${GTSAM_TOOLBOX_INSTALL_PATH}/gtsam/tests) + +# Examples +message(STATUS "Installing Matlab Toolbox Examples") +# Matlab files: *.m and *.fig +file(GLOB matlab_examples_m "${GTSAM_SOURCE_ROOT_DIR}/matlab/examples/*.m") +file(GLOB matlab_examples_fig "${GTSAM_SOURCE_ROOT_DIR}/matlab/examples/*.fig") +set(matlab_examples ${matlab_examples_m} ${matlab_examples_fig}) +install(FILES ${matlab_examples} DESTINATION ${GTSAM_TOOLBOX_INSTALL_PATH}/gtsam/examples) + +message(STATUS "Installing Matlab Toolbox Examples (Data)") +# Data files: *.graph and *.txt +file(GLOB matlab_examples_data_graph "${GTSAM_SOURCE_ROOT_DIR}/examples/Data/*.graph") +file(GLOB matlab_examples_data_txt "${GTSAM_SOURCE_ROOT_DIR}/examples/Data/*.txt") +set(matlab_examples_data ${matlab_examples_data_graph} ${matlab_examples_data_txt}) +install(FILES ${matlab_examples_data} DESTINATION ${GTSAM_TOOLBOX_INSTALL_PATH}/gtsam/Data) diff --git a/matlab/VisualISAMGenerateData.m b/matlab/VisualISAMGenerateData.m index 3c55417d9..1c71185e2 100644 --- a/matlab/VisualISAMGenerateData.m +++ b/matlab/VisualISAMGenerateData.m @@ -29,7 +29,7 @@ data.K = truth.K; for i=1:options.nrCameras theta = (i-1)*2*pi/options.nrCameras; t = gtsamPoint3([r*cos(theta), r*sin(theta), height]'); - truth.cameras{i} = gtsamSimpleCamera_lookat(t, gtsamPoint3, gtsamPoint3([0,0,1]'), truth.K); + truth.cameras{i} = gtsamSimpleCamera.Lookat(t, gtsamPoint3, gtsamPoint3([0,0,1]'), truth.K); % Create measurements for j=1:nrPoints % All landmarks seen in every frame diff --git a/matlab/VisualISAMInitialize.m b/matlab/VisualISAMInitialize.m index 139d40e65..b2b960a7b 100644 --- a/matlab/VisualISAMInitialize.m +++ b/matlab/VisualISAMInitialize.m @@ -6,10 +6,10 @@ function [noiseModels,isam,result] = VisualISAMInitialize(data,truth,options) isam = visualSLAMISAM(options.reorderInterval); %% Set Noise parameters -noiseModels.pose = gtsamnoiseModelDiagonal_Sigmas([0.001 0.001 0.001 0.1 0.1 0.1]'); -noiseModels.odometry = gtsamnoiseModelDiagonal_Sigmas([0.001 0.001 0.001 0.1 0.1 0.1]'); -noiseModels.point = gtsamnoiseModelIsotropic_Sigma(3, 0.1); -noiseModels.measurement = gtsamnoiseModelIsotropic_Sigma(2, 1.0); +noiseModels.pose = gtsamnoiseModelDiagonal.Sigmas([0.001 0.001 0.001 0.1 0.1 0.1]'); +noiseModels.odometry = gtsamnoiseModelDiagonal.Sigmas([0.001 0.001 0.001 0.1 0.1 0.1]'); +noiseModels.point = gtsamnoiseModelIsotropic.Sigma(3, 0.1); +noiseModels.measurement = gtsamnoiseModelIsotropic.Sigma(2, 1.0); %% Add constraints/priors % TODO: should not be from ground truth! diff --git a/matlab/examples/LocalizationExample.m b/matlab/examples/LocalizationExample.m index d3e563dd4..3f48bb8e4 100644 --- a/matlab/examples/LocalizationExample.m +++ b/matlab/examples/LocalizationExample.m @@ -20,13 +20,13 @@ graph = pose2SLAMGraph; %% Add two odometry factors odometry = gtsamPose2(2.0, 0.0, 0.0); % create a measurement for both factors (the same in this case) -odometryNoise = gtsamnoiseModelDiagonal_Sigmas([0.2; 0.2; 0.1]); % 20cm std on x,y, 0.1 rad on theta +odometryNoise = gtsamnoiseModelDiagonal.Sigmas([0.2; 0.2; 0.1]); % 20cm std on x,y, 0.1 rad on theta graph.addRelativePose(1, 2, odometry, odometryNoise); graph.addRelativePose(2, 3, odometry, odometryNoise); %% Add three "GPS" measurements % We use Pose2 Priors here with high variance on theta -noiseModel = gtsamnoiseModelDiagonal_Sigmas([0.1; 0.1; 10]); +noiseModel = gtsamnoiseModelDiagonal.Sigmas([0.1; 0.1; 10]); graph.addPosePrior(1, gtsamPose2(0.0, 0.0, 0.0), noiseModel); graph.addPosePrior(2, gtsamPose2(2.0, 0.0, 0.0), noiseModel); graph.addPosePrior(3, gtsamPose2(4.0, 0.0, 0.0), noiseModel); diff --git a/matlab/examples/OdometryExample.m b/matlab/examples/OdometryExample.m index b3cbff6a2..e90550152 100644 --- a/matlab/examples/OdometryExample.m +++ b/matlab/examples/OdometryExample.m @@ -20,12 +20,12 @@ graph = pose2SLAMGraph; %% Add a Gaussian prior on pose x_1 priorMean = gtsamPose2(0.0, 0.0, 0.0); % prior mean is at origin -priorNoise = gtsamnoiseModelDiagonal_Sigmas([0.3; 0.3; 0.1]); % 30cm std on x,y, 0.1 rad on theta +priorNoise = gtsamnoiseModelDiagonal.Sigmas([0.3; 0.3; 0.1]); % 30cm std on x,y, 0.1 rad on theta graph.addPosePrior(1, priorMean, priorNoise); % add directly to graph %% Add two odometry factors odometry = gtsamPose2(2.0, 0.0, 0.0); % create a measurement for both factors (the same in this case) -odometryNoise = gtsamnoiseModelDiagonal_Sigmas([0.2; 0.2; 0.1]); % 20cm std on x,y, 0.1 rad on theta +odometryNoise = gtsamnoiseModelDiagonal.Sigmas([0.2; 0.2; 0.1]); % 20cm std on x,y, 0.1 rad on theta graph.addRelativePose(1, 2, odometry, odometryNoise); graph.addRelativePose(2, 3, odometry, odometryNoise); diff --git a/matlab/examples/PlanarSLAMExample.m b/matlab/examples/PlanarSLAMExample.m index 499845eda..7557bd0ba 100644 --- a/matlab/examples/PlanarSLAMExample.m +++ b/matlab/examples/PlanarSLAMExample.m @@ -28,18 +28,18 @@ graph = planarSLAMGraph; %% Add prior priorMean = gtsamPose2(0.0, 0.0, 0.0); % prior at origin -priorNoise = gtsamnoiseModelDiagonal_Sigmas([0.3; 0.3; 0.1]); +priorNoise = gtsamnoiseModelDiagonal.Sigmas([0.3; 0.3; 0.1]); graph.addPosePrior(i1, priorMean, priorNoise); % add directly to graph %% Add odometry odometry = gtsamPose2(2.0, 0.0, 0.0); -odometryNoise = gtsamnoiseModelDiagonal_Sigmas([0.2; 0.2; 0.1]); +odometryNoise = gtsamnoiseModelDiagonal.Sigmas([0.2; 0.2; 0.1]); graph.addRelativePose(i1, i2, odometry, odometryNoise); graph.addRelativePose(i2, i3, odometry, odometryNoise); %% Add bearing/range measurement factors degrees = pi/180; -noiseModel = gtsamnoiseModelDiagonal_Sigmas([0.1; 0.2]); +noiseModel = gtsamnoiseModelDiagonal.Sigmas([0.1; 0.2]); graph.addBearingRange(i1, j1, gtsamRot2(45*degrees), sqrt(4+4), noiseModel); graph.addBearingRange(i2, j1, gtsamRot2(90*degrees), 2, noiseModel); graph.addBearingRange(i3, j2, gtsamRot2(90*degrees), 2, noiseModel); diff --git a/matlab/examples/PlanarSLAMExample_sampling.m b/matlab/examples/PlanarSLAMExample_sampling.m index 861e56db9..560ab7ace 100644 --- a/matlab/examples/PlanarSLAMExample_sampling.m +++ b/matlab/examples/PlanarSLAMExample_sampling.m @@ -15,22 +15,22 @@ i1 = symbol('x',1); i2 = symbol('x',2); i3 = symbol('x',3); graph = planarSLAMGraph; priorMean = gtsamPose2(0.0, 0.0, 0.0); % prior at origin -priorNoise = gtsamnoiseModelDiagonal_Sigmas([0.3; 0.3; 0.1]); +priorNoise = gtsamnoiseModelDiagonal.Sigmas([0.3; 0.3; 0.1]); graph.addPosePrior(i1, priorMean, priorNoise); % add directly to graph odometry = gtsamPose2(2.0, 0.0, 0.0); -odometryNoise = gtsamnoiseModelDiagonal_Sigmas([0.2; 0.2; 0.1]); +odometryNoise = gtsamnoiseModelDiagonal.Sigmas([0.2; 0.2; 0.1]); graph.addRelativePose(i1, i2, odometry, odometryNoise); graph.addRelativePose(i2, i3, odometry, odometryNoise); %% Except, for measurements we offer a choice j1 = symbol('l',1); j2 = symbol('l',2); degrees = pi/180; -noiseModel = gtsamnoiseModelDiagonal_Sigmas([0.1; 0.2]); +noiseModel = gtsamnoiseModelDiagonal.Sigmas([0.1; 0.2]); if 1 graph.addBearingRange(i1, j1, gtsamRot2(45*degrees), sqrt(4+4), noiseModel); graph.addBearingRange(i2, j1, gtsamRot2(90*degrees), 2, noiseModel); else - bearingModel = gtsamnoiseModelDiagonal_Sigmas(0.1); + bearingModel = gtsamnoiseModelDiagonal.Sigmas(0.1); graph.addBearing(i1, j1, gtsamRot2(45*degrees), bearingModel); graph.addBearing(i2, j1, gtsamRot2(90*degrees), bearingModel); end diff --git a/matlab/examples/Pose2SLAMExample.m b/matlab/examples/Pose2SLAMExample.m index 776260e3f..9cb5b8af4 100644 --- a/matlab/examples/Pose2SLAMExample.m +++ b/matlab/examples/Pose2SLAMExample.m @@ -24,19 +24,19 @@ graph = pose2SLAMGraph; %% Add prior % gaussian for prior priorMean = gtsamPose2(0.0, 0.0, 0.0); % prior at origin -priorNoise = gtsamnoiseModelDiagonal_Sigmas([0.3; 0.3; 0.1]); +priorNoise = gtsamnoiseModelDiagonal.Sigmas([0.3; 0.3; 0.1]); graph.addPosePrior(1, priorMean, priorNoise); % add directly to graph %% Add odometry % general noisemodel for odometry -odometryNoise = gtsamnoiseModelDiagonal_Sigmas([0.2; 0.2; 0.1]); +odometryNoise = gtsamnoiseModelDiagonal.Sigmas([0.2; 0.2; 0.1]); graph.addRelativePose(1, 2, gtsamPose2(2.0, 0.0, 0.0 ), odometryNoise); graph.addRelativePose(2, 3, gtsamPose2(2.0, 0.0, pi/2), odometryNoise); graph.addRelativePose(3, 4, gtsamPose2(2.0, 0.0, pi/2), odometryNoise); graph.addRelativePose(4, 5, gtsamPose2(2.0, 0.0, pi/2), odometryNoise); %% Add pose constraint -model = gtsamnoiseModelDiagonal_Sigmas([0.2; 0.2; 0.1]); +model = gtsamnoiseModelDiagonal.Sigmas([0.2; 0.2; 0.1]); graph.addRelativePose(5, 2, gtsamPose2(2.0, 0.0, pi/2), model); % print diff --git a/matlab/examples/Pose2SLAMExample_advanced.m b/matlab/examples/Pose2SLAMExample_advanced.m index 843ae7e1c..45d288e50 100644 --- a/matlab/examples/Pose2SLAMExample_advanced.m +++ b/matlab/examples/Pose2SLAMExample_advanced.m @@ -25,20 +25,20 @@ graph = pose2SLAMGraph; %% Add prior % gaussian for prior -priorNoise = gtsamnoiseModelDiagonal_Sigmas([0.3; 0.3; 0.1]); +priorNoise = gtsamnoiseModelDiagonal.Sigmas([0.3; 0.3; 0.1]); priorMean = gtsamPose2(0.0, 0.0, 0.0); % prior at origin graph.addPosePrior(1, priorMean, priorNoise); % add directly to graph %% Add odometry % general noisemodel for odometry -odometryNoise = gtsamnoiseModelDiagonal_Sigmas([0.2; 0.2; 0.1]); +odometryNoise = gtsamnoiseModelDiagonal.Sigmas([0.2; 0.2; 0.1]); odometry = gtsamPose2(2.0, 0.0, 0.0); % create a measurement for both factors (the same in this case) graph.addRelativePose(1, 2, odometry, odometryNoise); graph.addRelativePose(2, 3, odometry, odometryNoise); %% Add measurements % general noisemodel for measurements -measurementNoise = gtsamnoiseModelDiagonal_Sigmas([0.1; 0.2]); +measurementNoise = gtsamnoiseModelDiagonal.Sigmas([0.1; 0.2]); % print graph.print('full graph'); diff --git a/matlab/examples/Pose2SLAMExample_circle.m b/matlab/examples/Pose2SLAMExample_circle.m index e05a77186..c089f5949 100644 --- a/matlab/examples/Pose2SLAMExample_circle.m +++ b/matlab/examples/Pose2SLAMExample_circle.m @@ -11,7 +11,7 @@ %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% %% Create a hexagon of poses -hexagon = pose2SLAMValues_Circle(6,1.0); +hexagon = pose2SLAMValues.Circle(6,1.0); p0 = hexagon.pose(0); p1 = hexagon.pose(1); @@ -19,7 +19,7 @@ p1 = hexagon.pose(1); fg = pose2SLAMGraph; fg.addPoseConstraint(0, p0); delta = p0.between(p1); -covariance = gtsamnoiseModelDiagonal_Sigmas([0.05; 0.05; 5*pi/180]); +covariance = gtsamnoiseModelDiagonal.Sigmas([0.05; 0.05; 5*pi/180]); fg.addRelativePose(0,1, delta, covariance); fg.addRelativePose(1,2, delta, covariance); fg.addRelativePose(2,3, delta, covariance); diff --git a/matlab/examples/Pose2SLAMExample_graph.m b/matlab/examples/Pose2SLAMExample_graph.m index a2645a593..258730aaa 100644 --- a/matlab/examples/Pose2SLAMExample_graph.m +++ b/matlab/examples/Pose2SLAMExample_graph.m @@ -11,13 +11,13 @@ %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% %% Initialize graph, initial estimate, and odometry noise -model = gtsamnoiseModelDiagonal_Sigmas([0.05; 0.05; 5*pi/180]); +model = gtsamnoiseModelDiagonal.Sigmas([0.05; 0.05; 5*pi/180]); [graph,initial]=load2D('../../examples/Data/w100-odom.graph',model); initial.print(sprintf('Initial estimate:\n')); %% Add a Gaussian prior on pose x_1 priorMean = gtsamPose2(0.0, 0.0, 0.0); % prior mean is at origin -priorNoise = gtsamnoiseModelDiagonal_Sigmas([0.01; 0.01; 0.01]); +priorNoise = gtsamnoiseModelDiagonal.Sigmas([0.01; 0.01; 0.01]); graph.addPosePrior(0, priorMean, priorNoise); % add directly to graph %% Plot Initial Estimate diff --git a/matlab/examples/Pose2SLAMwSPCG.m b/matlab/examples/Pose2SLAMwSPCG.m index 3d0ce8da7..3e773689b 100644 --- a/matlab/examples/Pose2SLAMwSPCG.m +++ b/matlab/examples/Pose2SLAMwSPCG.m @@ -22,19 +22,19 @@ graph = pose2SLAMGraph; %% Add prior % gaussian for prior priorMean = gtsamPose2(0.0, 0.0, 0.0); % prior at origin -priorNoise = gtsamnoiseModelDiagonal_Sigmas([0.3; 0.3; 0.1]); +priorNoise = gtsamnoiseModelDiagonal.Sigmas([0.3; 0.3; 0.1]); graph.addPrior(1, priorMean, priorNoise); % add directly to graph %% Add odometry % general noisemodel for odometry -odometryNoise = gtsamnoiseModelDiagonal_Sigmas([0.2; 0.2; 0.1]); +odometryNoise = gtsamnoiseModelDiagonal.Sigmas([0.2; 0.2; 0.1]); graph.addOdometry(1, 2, gtsamPose2(2.0, 0.0, 0.0 ), odometryNoise); graph.addOdometry(2, 3, gtsamPose2(2.0, 0.0, pi/2), odometryNoise); graph.addOdometry(3, 4, gtsamPose2(2.0, 0.0, pi/2), odometryNoise); graph.addOdometry(4, 5, gtsamPose2(2.0, 0.0, pi/2), odometryNoise); %% Add pose constraint -model = gtsamnoiseModelDiagonal_Sigmas([0.2; 0.2; 0.1]); +model = gtsamnoiseModelDiagonal.Sigmas([0.2; 0.2; 0.1]); graph.addRelativePose(5, 2, gtsamPose2(2.0, 0.0, pi/2), model); % print diff --git a/matlab/examples/Pose3SLAMExample.m b/matlab/examples/Pose3SLAMExample.m index c335203eb..c1328585e 100644 --- a/matlab/examples/Pose3SLAMExample.m +++ b/matlab/examples/Pose3SLAMExample.m @@ -11,7 +11,7 @@ %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% %% Create a hexagon of poses -hexagon = pose3SLAMValues_Circle(6,1.0); +hexagon = pose3SLAMValues.Circle(6,1.0); p0 = hexagon.pose(0); p1 = hexagon.pose(1); @@ -19,7 +19,7 @@ p1 = hexagon.pose(1); fg = pose3SLAMGraph; fg.addPoseConstraint(0, p0); delta = p0.between(p1); -covariance = gtsamnoiseModelDiagonal_Sigmas([0.05; 0.05; 0.05; 5*pi/180; 5*pi/180; 5*pi/180]); +covariance = gtsamnoiseModelDiagonal.Sigmas([0.05; 0.05; 0.05; 5*pi/180; 5*pi/180; 5*pi/180]); fg.addRelativePose(0,1, delta, covariance); fg.addRelativePose(1,2, delta, covariance); fg.addRelativePose(2,3, delta, covariance); diff --git a/matlab/examples/Pose3SLAMExample_graph.m b/matlab/examples/Pose3SLAMExample_graph.m index f2c411d08..f39fc306b 100644 --- a/matlab/examples/Pose3SLAMExample_graph.m +++ b/matlab/examples/Pose3SLAMExample_graph.m @@ -16,7 +16,7 @@ N = 2500; filename = '../../examples/Data/sphere2500.txt'; %% Initialize graph, initial estimate, and odometry noise -model = gtsamnoiseModelDiagonal_Sigmas([0.05; 0.05; 0.05; 5*pi/180; 5*pi/180; 5*pi/180]); +model = gtsamnoiseModelDiagonal.Sigmas([0.05; 0.05; 0.05; 5*pi/180; 5*pi/180; 5*pi/180]); [graph,initial]=load3D(filename,model,true,N); %% Plot Initial Estimate diff --git a/matlab/examples/SBAExample.m b/matlab/examples/SBAExample.m index 9050d011d..82fdd4646 100644 --- a/matlab/examples/SBAExample.m +++ b/matlab/examples/SBAExample.m @@ -34,7 +34,7 @@ graph = sparseBAGraph; %% Add factors for all measurements -measurementNoise = gtsamnoiseModelIsotropic_Sigma(2,measurementNoiseSigma); +measurementNoise = gtsamnoiseModelIsotropic.Sigma(2,measurementNoiseSigma); for i=1:length(data.Z) for k=1:length(data.Z{i}) j = data.J{i}{k}; @@ -43,11 +43,11 @@ for i=1:length(data.Z) end %% Add Gaussian priors for a pose and a landmark to constrain the system -cameraPriorNoise = gtsamnoiseModelDiagonal_Sigmas(cameraNoiseSigmas); +cameraPriorNoise = gtsamnoiseModelDiagonal.Sigmas(cameraNoiseSigmas); firstCamera = gtsamSimpleCamera(truth.cameras{1}.pose, truth.K); graph.addSimpleCameraPrior(symbol('c',1), firstCamera, cameraPriorNoise); -pointPriorNoise = gtsamnoiseModelIsotropic_Sigma(3,pointNoiseSigma); +pointPriorNoise = gtsamnoiseModelIsotropic.Sigma(3,pointNoiseSigma); graph.addPointPrior(symbol('p',1), truth.points{1}, pointPriorNoise); %% Print the graph diff --git a/matlab/examples/SFMExample.m b/matlab/examples/SFMExample.m index 277f31648..3eef9f916 100644 --- a/matlab/examples/SFMExample.m +++ b/matlab/examples/SFMExample.m @@ -32,7 +32,7 @@ poseNoiseSigmas = [0.001 0.001 0.001 0.1 0.1 0.1]'; graph = visualSLAMGraph; %% Add factors for all measurements -measurementNoise = gtsamnoiseModelIsotropic_Sigma(2,measurementNoiseSigma); +measurementNoise = gtsamnoiseModelIsotropic.Sigma(2,measurementNoiseSigma); for i=1:length(data.Z) for k=1:length(data.Z{i}) j = data.J{i}{k}; @@ -41,9 +41,9 @@ for i=1:length(data.Z) end %% Add Gaussian priors for a pose and a landmark to constrain the system -posePriorNoise = gtsamnoiseModelDiagonal_Sigmas(poseNoiseSigmas); +posePriorNoise = gtsamnoiseModelDiagonal.Sigmas(poseNoiseSigmas); graph.addPosePrior(symbol('x',1), truth.cameras{1}.pose, posePriorNoise); -pointPriorNoise = gtsamnoiseModelIsotropic_Sigma(3,pointNoiseSigma); +pointPriorNoise = gtsamnoiseModelIsotropic.Sigma(3,pointNoiseSigma); graph.addPointPrior(symbol('p',1), truth.points{1}, pointPriorNoise); %% Print the graph diff --git a/matlab/examples/StereoVOExample.m b/matlab/examples/StereoVOExample.m index 99adaa82b..9cf838e94 100644 --- a/matlab/examples/StereoVOExample.m +++ b/matlab/examples/StereoVOExample.m @@ -31,7 +31,7 @@ graph.addPoseConstraint(x1, first_pose); %% Create realistic calibration and measurement noise model % format: fx fy skew cx cy baseline K = gtsamCal3_S2Stereo(1000, 1000, 0, 320, 240, 0.2); -stereo_model = gtsamnoiseModelDiagonal_Sigmas([1.0; 1.0; 1.0]); +stereo_model = gtsamnoiseModelDiagonal.Sigmas([1.0; 1.0; 1.0]); %% Add measurements % pose 1 diff --git a/matlab/examples/StereoVOExample_large.m b/matlab/examples/StereoVOExample_large.m index ef1211e2a..d57628fa1 100644 --- a/matlab/examples/StereoVOExample_large.m +++ b/matlab/examples/StereoVOExample_large.m @@ -14,7 +14,7 @@ % format: fx fy skew cx cy baseline calib = dlmread('../../examples/Data/VO_calibration.txt'); K = gtsamCal3_S2Stereo(calib(1), calib(2), calib(3), calib(4), calib(5), calib(6)); -stereo_model = gtsamnoiseModelDiagonal_Sigmas([1.0; 1.0; 1.0]); +stereo_model = gtsamnoiseModelDiagonal.Sigmas([1.0; 1.0; 1.0]); %% create empty graph and values graph = visualSLAMGraph; diff --git a/matlab/load3D.m b/matlab/load3D.m index 6ba861a92..b457ea1af 100644 --- a/matlab/load3D.m +++ b/matlab/load3D.m @@ -29,7 +29,7 @@ for i=1:n i=v{2}; if (~successive & i @@ -64,7 +65,7 @@ void Argument::matlab_unwrap(FileWriter& file, const string& matlabName) const { file.oss << cppType << " " << name << " = unwrap< "; file.oss << cppType << " >(" << matlabName; - if (is_ptr || is_ref) file.oss << ", \"" << matlabType << "\""; + if (is_ptr || is_ref) file.oss << ", \"ptr_" << matlabType << "\""; file.oss << ");" << endl; } diff --git a/wrap/Argument.h b/wrap/Argument.h index b4c3fe4a7..4dcf6b563 100644 --- a/wrap/Argument.h +++ b/wrap/Argument.h @@ -14,6 +14,7 @@ * @brief arguments to constructors and methods * @author Frank Dellaert * @author Andrew Melim + * @author Richard Roberts **/ #pragma once diff --git a/wrap/CMakeLists.txt b/wrap/CMakeLists.txt index 866ee7a3f..14d9a1f84 100644 --- a/wrap/CMakeLists.txt +++ b/wrap/CMakeLists.txt @@ -1,6 +1,6 @@ # Build/install Wrap -find_package(Boost 1.42 COMPONENTS system filesystem thread REQUIRED) +set(WRAP_BOOST_LIBRARIES ${Boost_SYSTEM_LIBRARY} ${Boost_FILESYSTEM_LIBRARY} ${Boost_THREAD_LIBRARY}) # Build the executable itself file(GLOB wrap_srcs "*.cpp") @@ -9,19 +9,21 @@ list(REMOVE_ITEM wrap_srcs ${CMAKE_CURRENT_SOURCE_DIR}/wrap.cpp) add_library(wrap_lib STATIC ${wrap_srcs} ${wrap_headers}) gtsam_assign_source_folders(${wrap_srcs} ${wrap_headers}) add_executable(wrap wrap.cpp) -target_link_libraries(wrap wrap_lib ${Boost_SYSTEM_LIBRARY} ${Boost_FILESYSTEM_LIBRARY}) +target_link_libraries(wrap wrap_lib ${WRAP_BOOST_LIBRARIES}) -# Install wrap binary +# Install wrap binary and export target if (GTSAM_INSTALL_WRAP) - install(TARGETS wrap DESTINATION bin) + install(TARGETS wrap EXPORT GTSAM-exports DESTINATION bin) + list(APPEND GTSAM_EXPORTED_TARGETS wrap) + set(GTSAM_EXPORTED_TARGETS "${GTSAM_EXPORTED_TARGETS}" PARENT_SCOPE) endif(GTSAM_INSTALL_WRAP) # Install matlab header install(FILES matlab.h DESTINATION include/wrap) # Build tests -if (GTSAM_BUILD_TESTS) - set(wrap_local_libs wrap_lib ${Boost_SYSTEM_LIBRARY} ${Boost_FILESYSTEM_LIBRARY}) +if (GTSAM_BUILD_TESTS) + set(wrap_local_libs wrap_lib ${WRAP_BOOST_LIBRARIES}) gtsam_add_subdir_tests("wrap" "${wrap_local_libs}" "${wrap_local_libs}" "") endif(GTSAM_BUILD_TESTS) diff --git a/wrap/Class.cpp b/wrap/Class.cpp index aae97de37..2cb36386a 100644 --- a/wrap/Class.cpp +++ b/wrap/Class.cpp @@ -1,176 +1,317 @@ -/* ---------------------------------------------------------------------------- - - * 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 Class.cpp - * @author Frank Dellaert - * @author Andrew Melim - **/ - -#include -#include -#include - -#include - -#include "Class.h" -#include "utilities.h" -#include "Argument.h" - -using namespace std; -using namespace wrap; - -/* ************************************************************************* */ -void Class::matlab_proxy(const string& classFile) const { - // open destination classFile - FileWriter file(classFile, verbose_, "%"); - - // get the name of actual matlab object - string matlabName = qualifiedName(); - - // emit class proxy code - // we want our class to inherit the handle class for memory purposes - file.oss << "classdef " << matlabName << " < handle" << endl; - file.oss << " properties" << endl; - file.oss << " self = 0" << endl; - file.oss << " end" << endl; - file.oss << " methods" << endl; - // constructor - file.oss << " function obj = " << matlabName << "(varargin)" << endl; - //i is constructor id - int id = 0; - BOOST_FOREACH(ArgumentList a, constructor.args_list) - { - constructor.matlab_proxy_fragment(file,matlabName, id, a); - id++; - } - //Static constructor collect call - file.oss << " if nargin ==14, new_" << matlabName << "(varargin{1},0); end" << endl; - file.oss << " if nargin ~= 13 && nargin ~= 14 && obj.self == 0, error('" << matlabName << " constructor failed'); end" << endl; - file.oss << " end" << endl; - // deconstructor - file.oss << " function delete(obj)" << endl; - file.oss << " if obj.self ~= 0" << endl; - //TODO: Add verbosity flag - //file.oss << " fprintf(1,'MATLAB class deleting %x',obj.self);" << endl; - file.oss << " new_" << matlabName << "(obj.self);" << endl; - file.oss << " obj.self = 0;" << endl; - file.oss << " end" << endl; - file.oss << " end" << endl; - file.oss << " function display(obj), obj.print(''); end" << endl; - file.oss << " function disp(obj), obj.display; end" << endl; - file.oss << " end" << endl; - file.oss << "end" << endl; - - // close file - file.emit(true); -} - -/* ************************************************************************* */ -//TODO: Consolidate into single file -void Class::matlab_constructors(const string& toolboxPath) const { - /*BOOST_FOREACH(Constructor c, constructors) { - args_list.push_back(c.args); - }*/ - - BOOST_FOREACH(ArgumentList a, constructor.args_list) { - constructor.matlab_mfile(toolboxPath, qualifiedName(), a); - } - constructor.matlab_wrapper(toolboxPath, qualifiedName("::"), qualifiedName(), - using_namespaces, includes); -} - -/* ************************************************************************* */ -void Class::matlab_methods(const string& classPath) const { - string matlabName = qualifiedName(), cppName = qualifiedName("::"); - BOOST_FOREACH(Method m, methods) { - m.matlab_mfile (classPath); - m.matlab_wrapper(classPath, name, cppName, matlabName, using_namespaces, includes); - } -} - -/* ************************************************************************* */ -void Class::matlab_static_methods(const string& toolboxPath) const { - string matlabName = qualifiedName(), cppName = qualifiedName("::"); - BOOST_FOREACH(const StaticMethod& m, static_methods) { - m.matlab_mfile (toolboxPath, qualifiedName()); - m.matlab_wrapper(toolboxPath, name, matlabName, cppName, using_namespaces, includes); - } -} - -/* ************************************************************************* */ -void Class::matlab_make_fragment(FileWriter& file, - const string& toolboxPath, - const string& mexFlags) const { - string mex = "mex " + mexFlags + " "; - string matlabClassName = qualifiedName(); - file.oss << mex << constructor.matlab_wrapper_name(matlabClassName) << ".cpp" << endl; - BOOST_FOREACH(StaticMethod sm, static_methods) - file.oss << mex << matlabClassName + "_" + sm.name << ".cpp" << endl; - file.oss << endl << "cd @" << matlabClassName << endl; - BOOST_FOREACH(Method m, methods) - file.oss << mex << m.name << ".cpp" << endl; - file.oss << endl; -} - -/* ************************************************************************* */ -void Class::makefile_fragment(FileWriter& file) const { -// new_Point2_.$(MEXENDING): new_Point2_.cpp -// $(MEX) $(mex_flags) new_Point2_.cpp -// new_Point2_dd.$(MEXENDING): new_Point2_dd.cpp -// $(MEX) $(mex_flags) new_Point2_dd.cpp -// @Point2/x.$(MEXENDING): @Point2/x.cpp -// $(MEX) $(mex_flags) @Point2/x.cpp -output @Point2/x -// @Point2/y.$(MEXENDING): @Point2/y.cpp -// $(MEX) $(mex_flags) @Point2/y.cpp -output @Point2/y -// @Point2/dim.$(MEXENDING): @Point2/dim.cpp -// $(MEX) $(mex_flags) @Point2/dim.cpp -output @Point2/dim -// -// Point2: new_Point2_.$(MEXENDING) new_Point2_dd.$(MEXENDING) @Point2/x.$(MEXENDING) @Point2/y.$(MEXENDING) @Point2/dim.$(MEXENDING) - - string matlabName = qualifiedName(); - - // collect names - vector file_names; - string file_base = constructor.matlab_wrapper_name(matlabName); - file_names.push_back(file_base); - BOOST_FOREACH(StaticMethod c, static_methods) { - string file_base = matlabName + "_" + c.name; - file_names.push_back(file_base); - } - BOOST_FOREACH(Method c, methods) { - string file_base = "@" + matlabName + "/" + c.name; - file_names.push_back(file_base); - } - - BOOST_FOREACH(const string& file_base, file_names) { - file.oss << file_base << ".$(MEXENDING): " << file_base << ".cpp"; - file.oss << " $(PATH_TO_WRAP)/matlab.h" << endl; - file.oss << "\t$(MEX) $(mex_flags) " << file_base << ".cpp -output " << file_base << endl; - } - - // class target - file.oss << "\n" << matlabName << ": "; - BOOST_FOREACH(const string& file_base, file_names) { - file.oss << file_base << ".$(MEXENDING) "; - } - file.oss << "\n" << endl; -} - -/* ************************************************************************* */ -string Class::qualifiedName(const string& delim) const { - string result; - BOOST_FOREACH(const string& ns, namespaces) - result += ns + delim; - return result + name; -} - -/* ************************************************************************* */ +/* ---------------------------------------------------------------------------- + + * 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 Class.cpp + * @author Frank Dellaert + * @author Andrew Melim + * @author Richard Roberts + **/ + +#include +#include +#include +//#include // on Linux GCC: fails with error regarding needing C++0x std flags +//#include // same failure as above +#include // works on Linux GCC + +#include +#include + +#include "Class.h" +#include "utilities.h" +#include "Argument.h" + +using namespace std; +using namespace wrap; + +/* ************************************************************************* */ +void Class::matlab_proxy(const string& classFile, const string& wrapperName, + const TypeAttributesTable& typeAttributes, + FileWriter& wrapperFile, vector& functionNames) const { + // open destination classFile + FileWriter proxyFile(classFile, verbose_, "%"); + + // get the name of actual matlab object + const string matlabName = qualifiedName(), cppName = qualifiedName("::"); + const string matlabBaseName = wrap::qualifiedName("", qualifiedParent); + const string cppBaseName = wrap::qualifiedName("::", qualifiedParent); + + // emit class proxy code + // we want our class to inherit the handle class for memory purposes + const string parent = qualifiedParent.empty() ? + "handle" : ::wrap::qualifiedName("", qualifiedParent); + proxyFile.oss << "classdef " << matlabName << " < " << parent << endl; + proxyFile.oss << " properties" << endl; + proxyFile.oss << " ptr_" << matlabName << " = 0" << endl; + proxyFile.oss << " end" << endl; + proxyFile.oss << " methods" << endl; + + // Constructor + proxyFile.oss << " function obj = " << matlabName << "(varargin)" << endl; + // 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 + // its collector. This allows wrapped functions to return objects in + // other wrap modules - to add these to their collectors the pointer is + // passed from one C++ module into matlab then back into the other C++ + // module. + pointer_constructor_fragments(proxyFile, wrapperFile, wrapperName, functionNames); + wrapperFile.oss << "\n"; + // Regular constructors + BOOST_FOREACH(ArgumentList a, constructor.args_list) + { + const int id = (int)functionNames.size(); + constructor.proxy_fragment(proxyFile, wrapperName, matlabName, matlabBaseName, id, a); + const string wrapFunctionName = constructor.wrapper_fragment(wrapperFile, + cppName, matlabName, cppBaseName, id, using_namespaces, a); + wrapperFile.oss << "\n"; + functionNames.push_back(wrapFunctionName); + } + proxyFile.oss << " else\n"; + proxyFile.oss << " error('Arguments do not match any overload of " << matlabName << " constructor');" << endl; + proxyFile.oss << " end\n"; + if(!qualifiedParent.empty()) + proxyFile.oss << " obj = obj@" << matlabBaseName << "(uint64(" << ptr_constructor_key << "), base_ptr);\n"; + proxyFile.oss << " obj.ptr_" << matlabName << " = my_ptr;\n"; + proxyFile.oss << " end\n\n"; + + // Deconstructor + { + const int id = (int)functionNames.size(); + deconstructor.proxy_fragment(proxyFile, wrapperName, matlabName, id); + proxyFile.oss << "\n"; + const string functionName = deconstructor.wrapper_fragment(wrapperFile, cppName, matlabName, id, using_namespaces); + wrapperFile.oss << "\n"; + functionNames.push_back(functionName); + } + proxyFile.oss << " function display(obj), obj.print(''); end\n\n"; + proxyFile.oss << " function disp(obj), obj.display; end\n\n"; + + // Methods + BOOST_FOREACH(const Methods::value_type& name_m, methods) { + const Method& m = name_m.second; + m.proxy_wrapper_fragments(proxyFile, wrapperFile, cppName, matlabName, wrapperName, using_namespaces, typeAttributes, functionNames); + proxyFile.oss << "\n"; + wrapperFile.oss << "\n"; + } + + proxyFile.oss << " end\n"; + proxyFile.oss << "\n"; + proxyFile.oss << " methods(Static = true)\n"; + + // Static methods + BOOST_FOREACH(const StaticMethods::value_type& name_m, static_methods) { + const StaticMethod& m = name_m.second; + m.proxy_wrapper_fragments(proxyFile, wrapperFile, cppName, matlabName, wrapperName, using_namespaces, typeAttributes, functionNames); + proxyFile.oss << "\n"; + wrapperFile.oss << "\n"; + } + + proxyFile.oss << " end" << endl; + proxyFile.oss << "end" << endl; + + // Close file + proxyFile.emit(true); +} + +/* ************************************************************************* */ +string Class::qualifiedName(const string& delim) const { + return ::wrap::qualifiedName(delim, namespaces, name); +} + +/* ************************************************************************* */ +void Class::pointer_constructor_fragments(FileWriter& proxyFile, FileWriter& wrapperFile, const string& wrapperName, vector& functionNames) const { + + const string matlabName = qualifiedName(), cppName = qualifiedName("::"); + const string baseMatlabName = wrap::qualifiedName("", qualifiedParent); + const string baseCppName = wrap::qualifiedName("::", qualifiedParent); + + const int collectorInsertId = (int)functionNames.size(); + const string collectorInsertFunctionName = matlabName + "_collectorInsertAndMakeBase_" + boost::lexical_cast(collectorInsertId); + functionNames.push_back(collectorInsertFunctionName); + + int upcastFromVoidId; + string upcastFromVoidFunctionName; + if(isVirtual) { + upcastFromVoidId = (int)functionNames.size(); + upcastFromVoidFunctionName = matlabName + "_upcastFromVoid_" + boost::lexical_cast(upcastFromVoidId); + functionNames.push_back(upcastFromVoidFunctionName); + } + + // MATLAB constructor that assigns pointer to matlab object then calls c++ + // function to add the object to the collector. + if(isVirtual) { + proxyFile.oss << " if (nargin == 2 || (nargin == 3 && strcmp(varargin{3}, 'void')))"; + } else { + proxyFile.oss << " if nargin == 2"; + } + proxyFile.oss << " && isa(varargin{1}, 'uint64') && varargin{1} == uint64(" << ptr_constructor_key << ")\n"; + if(isVirtual) { + proxyFile.oss << " if nargin == 2\n"; + proxyFile.oss << " my_ptr = varargin{2};\n"; + proxyFile.oss << " else\n"; + proxyFile.oss << " my_ptr = " << wrapperName << "(" << upcastFromVoidId << ", varargin{2});\n"; + proxyFile.oss << " end\n"; + } 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 + proxyFile.oss << " "; + else + proxyFile.oss << " base_ptr = "; + proxyFile.oss << wrapperName << "(" << collectorInsertId << ", my_ptr);\n"; // Call collector insert and get base class ptr + + // C++ function to add pointer from MATLAB to collector. The pointer always + // comes from a C++ return value; this mechanism allows the object to be added + // to a collector in a different wrap module. If this class has a base class, + // a new pointer to the base class is allocated and returned. + wrapperFile.oss << "void " << collectorInsertFunctionName << "(int nargout, mxArray *out[], int nargin, const mxArray *in[])" << endl; + wrapperFile.oss << "{\n"; + wrapperFile.oss << " mexAtExit(&_deleteAllObjects);\n"; + generateUsingNamespace(wrapperFile, using_namespaces); + // Typedef boost::shared_ptr + wrapperFile.oss << " typedef boost::shared_ptr<" << cppName << "> Shared;\n"; + wrapperFile.oss << "\n"; + // Get self pointer passed in + wrapperFile.oss << " Shared *self = *reinterpret_cast (mxGetData(in[0]));\n"; + // Add to collector + wrapperFile.oss << " collector_" << matlabName << ".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()) { + wrapperFile.oss << "\n"; + wrapperFile.oss << " typedef boost::shared_ptr<" << baseCppName << "> SharedBase;\n"; + wrapperFile.oss << " out[0] = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL);\n"; + wrapperFile.oss << " *reinterpret_cast(mxGetData(out[0])) = new SharedBase(*self);\n"; + } + wrapperFile.oss << "}\n"; + + // If this is a virtual function, C++ function to dynamic upcast it from a + // shared_ptr. This mechanism allows automatic dynamic creation of the + // real underlying derived-most class when a C++ method returns a virtual + // base class. + if(isVirtual) + wrapperFile.oss << + "\n" + "void " << upcastFromVoidFunctionName << "(int nargout, mxArray *out[], int nargin, const mxArray *in[]) {\n" + " mexAtExit(&_deleteAllObjects);\n" + " typedef boost::shared_ptr<" << cppName << "> Shared;\n" + " boost::shared_ptr *asVoid = *reinterpret_cast**> (mxGetData(in[0]));\n" + " out[0] = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL);\n" + " Shared *self = new Shared(boost::static_pointer_cast<" << cppName << ">(*asVoid));\n" + " *reinterpret_cast(mxGetData(out[0])) = self;\n" + "}\n"; +} + +/* ************************************************************************* */ +vector expandArgumentListsTemplate(const vector& argLists, const string& templateArg, const vector& instName) { + vector result; + BOOST_FOREACH(const ArgumentList& argList, argLists) { + ArgumentList instArgList; + BOOST_FOREACH(const Argument& arg, argList) { + Argument instArg = arg; + if(arg.type == templateArg) { + instArg.namespaces.assign(instName.begin(), instName.end()-1); + instArg.type = instName.back(); + } + instArgList.push_back(instArg); + } + result.push_back(instArgList); + } + return result; +} + +/* ************************************************************************* */ +template +map expandMethodTemplate(const map& methods, const string& templateArg, const vector& instName) { + map result; + typedef pair Name_Method; + BOOST_FOREACH(const Name_Method& name_method, methods) { + const METHOD& method = name_method.second; + METHOD instMethod = method; + instMethod.argLists = expandArgumentListsTemplate(method.argLists, templateArg, instName); + instMethod.returnVals.clear(); + BOOST_FOREACH(const ReturnValue& retVal, method.returnVals) { + ReturnValue instRetVal = retVal; + if(retVal.type1 == templateArg) { + instRetVal.namespaces1.assign(instName.begin(), instName.end()-1); + instRetVal.type1 = instName.back(); + } + if(retVal.type2 == templateArg) { + instRetVal.namespaces2.assign(instName.begin(), instName.end()-1); + instRetVal.type2 = instName.back(); + } + instMethod.returnVals.push_back(instRetVal); + } + result.insert(make_pair(name_method.first, instMethod)); + } + return result; +} + +/* ************************************************************************* */ +Class expandClassTemplate(const Class& cls, const string& templateArg, const vector& instName) { + Class inst; + inst.name = cls.name; + inst.templateArgs = cls.templateArgs; + inst.typedefName = cls.typedefName; + inst.isVirtual = cls.isVirtual; + inst.qualifiedParent = cls.qualifiedParent; + inst.methods = expandMethodTemplate(cls.methods, templateArg, instName); + inst.static_methods = expandMethodTemplate(cls.static_methods, templateArg, instName); + inst.namespaces = cls.namespaces; + inst.using_namespaces = cls.using_namespaces; + bool allIncludesEmpty = true; + BOOST_FOREACH(const string& inc, cls.includes) { if(!inc.empty()) { allIncludesEmpty = false; break; } } + if(allIncludesEmpty) + inst.includes.push_back(cls.name + ".h"); + else + inst.includes = cls.includes; + inst.constructor = cls.constructor; + inst.constructor.args_list = expandArgumentListsTemplate(cls.constructor.args_list, templateArg, instName); + inst.constructor.name = inst.name; + inst.deconstructor = cls.deconstructor; + inst.deconstructor.name = inst.name; + inst.verbose_ = cls.verbose_; + return inst; +} + +/* ************************************************************************* */ +vector Class::expandTemplate(const string& templateArg, const vector >& instantiations) const { + vector result; + BOOST_FOREACH(const vector& instName, instantiations) { + Class inst = expandClassTemplate(*this, templateArg, instName); + inst.name = name + instName.back(); + inst.templateArgs.clear(); + inst.typedefName = qualifiedName("::") + "<" + wrap::qualifiedName("::", instName) + ">"; + result.push_back(inst); + } + return result; +} + +/* ************************************************************************* */ +Class Class::expandTemplate(const string& templateArg, const vector& instantiation) const { + return expandClassTemplate(*this, templateArg, instantiation); +} + +/* ************************************************************************* */ +std::string Class::getTypedef() const { + string result; + BOOST_FOREACH(const string& namesp, namespaces) { + result += ("namespace " + namesp + " { "); + } + result += ("typedef " + typedefName + " " + name + ";"); + BOOST_FOREACH(const string& namesp, namespaces) { + result += " }"; + } + return result; +} + +/* ************************************************************************* */ diff --git a/wrap/Class.h b/wrap/Class.h index fb9906716..beee2c29f 100644 --- a/wrap/Class.h +++ b/wrap/Class.h @@ -14,44 +14,58 @@ * @brief describe the C++ class that is being wrapped * @author Frank Dellaert * @author Andrew Melim + * @author Richard Roberts **/ #pragma once #include +#include #include "Constructor.h" #include "Deconstructor.h" #include "Method.h" #include "StaticMethod.h" +#include "TypeAttributesTable.h" namespace wrap { /// Class has name, constructors, methods struct Class { + typedef std::map Methods; + typedef std::map StaticMethods; + /// Constructor creates an empty class - Class(bool verbose=true) : verbose_(verbose) {} + Class(bool verbose=true) : isVirtual(false), verbose_(verbose) {} // Then the instance variables are set directly by the Module constructor std::string name; ///< Class name - std::vector methods; ///< Class methods - std::vector static_methods; ///< Static methods + std::vector templateArgs; ///< Template arguments + std::string typedefName; ///< The name to typedef *from*, if this class is actually a typedef, i.e. typedef [typedefName] [name] + bool isVirtual; ///< Whether the class is part of a virtual inheritance chain + std::vector qualifiedParent; ///< The *single* parent - the last string is the parent class name, preceededing elements are a namespace stack + Methods methods; ///< Class methods + StaticMethods static_methods; ///< Static methods std::vector namespaces; ///< Stack of namespaces - std::vector using_namespaces; ///< default namespaces + std::vector using_namespaces;///< default namespaces std::vector includes; ///< header include overrides - Constructor constructor; ///< Class constructors + Constructor constructor; ///< Class constructors + Deconstructor deconstructor; ///< Deconstructor to deallocate C++ object bool verbose_; ///< verbose flag // And finally MATLAB code is emitted, methods below called by Module::matlab_code - void matlab_proxy(const std::string& classFile) const; ///< emit proxy class - void matlab_constructors(const std::string& toolboxPath) const; ///< emit constructor wrappers - void matlab_methods(const std::string& classPath) const; ///< emit method wrappers - void matlab_static_methods(const std::string& classPath) const; ///< emit static method wrappers - void matlab_make_fragment(FileWriter& file, - const std::string& toolboxPath, - const std::string& mexFlags) const; ///< emit make fragment for global make script - void makefile_fragment(FileWriter& file) const; ///< emit makefile fragment + void matlab_proxy(const std::string& classFile, const std::string& wrapperName, const TypeAttributesTable& typeAttributes, + FileWriter& wrapperFile, std::vector& functionNames) const; ///< emit proxy class std::string qualifiedName(const std::string& delim = "") const; ///< creates a namespace-qualified name, optional delimiter + + std::vector expandTemplate(const std::string& templateArg, const std::vector >& instantiations) const; + Class expandTemplate(const std::string& templateArg, const std::vector& instantiation) const; + + // The typedef line for this class, if this class is a typedef, otherwise returns an empty string. + std::string getTypedef() const; + +private: + void pointer_constructor_fragments(FileWriter& proxyFile, FileWriter& wrapperFile, const std::string& wrapperName, std::vector& functionNames) const; }; } // \namespace wrap diff --git a/wrap/Constructor.cpp b/wrap/Constructor.cpp index 978516b18..afb35f62d 100644 --- a/wrap/Constructor.cpp +++ b/wrap/Constructor.cpp @@ -13,6 +13,7 @@ * @file Constructor.ccp * @author Frank Dellaert * @author Andrew Melim + * @author Richard Roberts **/ #include @@ -20,6 +21,7 @@ #include #include +#include #include "utilities.h" #include "Constructor.h" @@ -35,11 +37,11 @@ string Constructor::matlab_wrapper_name(const string& className) const { } /* ************************************************************************* */ -void Constructor::matlab_proxy_fragment(FileWriter& file, - const string& className, const int id, const ArgumentList args) const { +void Constructor::proxy_fragment(FileWriter& file, const std::string& wrapperName, + const string& matlabName, const string& matlabBaseName, const int id, const ArgumentList args) const { size_t nrArgs = args.size(); // check for number of arguments... - file.oss << " if (nargin == " << nrArgs; + file.oss << " elseif nargin == " << nrArgs; if (nrArgs>0) file.oss << " && "; // ...and their types bool first = true; @@ -49,117 +51,60 @@ void Constructor::matlab_proxy_fragment(FileWriter& file, first=false; } // emit code for calling constructor - file.oss << "), obj.self = " << matlab_wrapper_name(className) << "(" << "0," << id; + if(matlabBaseName.empty()) + file.oss << "\n my_ptr = "; + else + file.oss << "\n [ my_ptr, base_ptr ] = "; + file.oss << wrapperName << "(" << id; // emit constructor arguments for(size_t i=0;i& using_namespaces, - const vector& includes) const { - string matlabName = matlab_wrapper_name(matlabClassName); + const ArgumentList& al) const { - // open destination wrapperFile - string wrapperFile = toolboxPath + "/" + matlabName + ".cpp"; - FileWriter file(wrapperFile, verbose_, "//"); - - // generate code - generateIncludes(file, name, includes); - generateUsingNamespace(file, using_namespaces); + const string wrapFunctionName = matlabClassName + "_constructor_" + boost::lexical_cast(id); + file.oss << "void " << wrapFunctionName << "(int nargout, mxArray *out[], int nargin, const mxArray *in[])" << endl; + file.oss << "{\n"; + file.oss << " mexAtExit(&_deleteAllObjects);\n"; + generateUsingNamespace(file, using_namespaces); //Typedef boost::shared_ptr - file.oss << "typedef boost::shared_ptr<" << cppClassName << "> Shared;" << endl; - file.oss << endl; + file.oss << " typedef boost::shared_ptr<" << cppClassName << "> Shared;\n"; + file.oss << "\n"; - //Generate collector - file.oss << "static std::set collector;" << endl; - file.oss << endl; + //Check to see if there will be any arguments and remove {} for consiseness + if(al.size() > 0) + al.matlab_unwrap(file); // unwrap arguments + file.oss << " Shared *self = new Shared(new " << cppClassName << "(" << al.names() << "));" << endl; + file.oss << " collector_" << matlabClassName << ".insert(self);\n"; - //Generate cleanup function - file.oss << "void cleanup(void) {" << endl; - file.oss << " for(std::set::iterator iter = collector.begin(); iter != collector.end(); ) {\n"; - file.oss << " delete *iter;\n"; - file.oss << " collector.erase(iter++);\n"; - file.oss << " }\n"; - file.oss << "}" << endl; + if(verbose_) + file.oss << " std::cout << \"constructed \" << self << \" << std::endl;" << endl; + file.oss << " out[0] = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL);" << endl; + file.oss << " *reinterpret_cast (mxGetData(out[0])) = self;" << endl; - file.oss << "void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[])" << endl; - file.oss << "{" << endl; - //Cleanup function callback - file.oss << " mexAtExit(cleanup);" << endl; - file.oss << endl; - file.oss << " const mxArray* input = in[0];" << endl; - file.oss << " Shared* self = *(Shared**) mxGetData(input);" << endl; - file.oss << endl; - file.oss << " if(self) {" << endl; - file.oss << " if(nargin > 1) {" << endl; - file.oss << " collector.insert(self);" << endl; - if(verbose_) - file.oss << " std::cout << \"Collected\" << collector.size() << std::endl;" << endl; - file.oss << " }" << endl; - file.oss << " else if(collector.erase(self))" << endl; - file.oss << " delete self;" << endl; - file.oss << " } else {" << endl; - file.oss << " int nc = unwrap(in[1]);" << endl << endl; - - int i = 0; - BOOST_FOREACH(ArgumentList al, args_list) - { - //Check to see if there will be any arguments and remove {} for consiseness - if(al.size()) - { - file.oss << " if(nc == " << i <<") {" << endl; - al.matlab_unwrap(file, 2); // unwrap arguments, start at 1 - file.oss << " self = new Shared(new " << cppClassName << "(" << al.names() << "));" << endl; - file.oss << " }" << endl; - } - else - { - file.oss << " if(nc == " << i <<")" << endl; - file.oss << " self = new Shared(new " << cppClassName << "(" << al.names() << "));" << endl; - } - i++; - } - - //file.oss << " self = construct(nc, in);" << endl; - file.oss << " collector.insert(self);" << endl; - if(verbose_) - file.oss << " std::cout << \"constructed \" << self << \", size=\" << collector.size() << std::endl;" << endl; - file.oss << " out[0] = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL);" << endl; - file.oss << " *reinterpret_cast (mxGetPr(out[0])) = self;" << endl; - file.oss << " }" << 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()) { + file.oss << "\n"; + file.oss << " typedef boost::shared_ptr<" << cppBaseClassName << "> SharedBase;\n"; + file.oss << " out[1] = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL);\n"; + file.oss << " *reinterpret_cast(mxGetData(out[1])) = new SharedBase(*self);\n"; + } file.oss << "}" << endl; - // close file - file.emit(true); + return wrapFunctionName; } /* ************************************************************************* */ diff --git a/wrap/Constructor.h b/wrap/Constructor.h index 467ff3b22..50d0c41f5 100644 --- a/wrap/Constructor.h +++ b/wrap/Constructor.h @@ -13,6 +13,7 @@ * @file Constructor.h * @brief class describing a constructor + code generation * @author Frank Dellaert + * @author Richard Roberts **/ #pragma once @@ -48,21 +49,18 @@ struct Constructor { * Create fragment to select constructor in proxy class, e.g., * if nargin == 2, obj.self = new_Pose3_RP(varargin{1},varargin{2}); end */ - void matlab_proxy_fragment(FileWriter& file, - const std::string& className, const int i, + void proxy_fragment(FileWriter& file, const std::string& wrapperName, + const std::string& className, const std::string& matlabBaseName, const int id, const ArgumentList args) const; - /// m-file - void matlab_mfile(const std::string& toolboxPath, - const std::string& qualifiedMatlabName, - const ArgumentList args) const; - /// cpp wrapper - void matlab_wrapper(const std::string& toolboxPath, + std::string wrapper_fragment(FileWriter& file, const std::string& cppClassName, const std::string& matlabClassName, + const std::string& cppBaseClassName, + int id, const std::vector& using_namespaces, - const std::vector& includes) const; + const ArgumentList& al) const; /// constructor function void generate_construct(FileWriter& file, const std::string& cppClassName, diff --git a/wrap/Deconstructor.cpp b/wrap/Deconstructor.cpp index 93ed724f5..c02ab0e93 100644 --- a/wrap/Deconstructor.cpp +++ b/wrap/Deconstructor.cpp @@ -13,12 +13,14 @@ * @file Deconstructor.ccp * @author Frank Dellaert * @author Andrew Melim + * @author Richard Roberts **/ #include #include #include +#include #include "utilities.h" #include "Deconstructor.h" @@ -33,51 +35,42 @@ string Deconstructor::matlab_wrapper_name(const string& className) const { } /* ************************************************************************* */ -void Deconstructor::matlab_mfile(const string& toolboxPath, const string& qualifiedMatlabName) const { +void Deconstructor::proxy_fragment(FileWriter& file, + const std::string& wrapperName, + const std::string& qualifiedMatlabName, int id) const { - string matlabName = matlab_wrapper_name(qualifiedMatlabName); - - // open destination m-file - string wrapperFile = toolboxPath + "/" + matlabName + ".m"; - FileWriter file(wrapperFile, verbose_, "%"); - - // generate code - file.oss << "function result = " << matlabName << "(obj"; - if (args.size()) file.oss << "," << args.names(); - file.oss << ")" << endl; - file.oss << " error('need to compile " << matlabName << ".cpp');" << endl; - file.oss << "end" << endl; - - // close file - file.emit(true); + file.oss << " function delete(obj)\n"; + file.oss << " " << wrapperName << "(" << id << ", obj.ptr_" << qualifiedMatlabName << ");\n"; + file.oss << " end\n"; } /* ************************************************************************* */ -void Deconstructor::matlab_wrapper(const string& toolboxPath, +string Deconstructor::wrapper_fragment(FileWriter& file, const string& cppClassName, const string& matlabClassName, - const vector& using_namespaces, const vector& includes) const { - string matlabName = matlab_wrapper_name(matlabClassName); + int id, + const vector& using_namespaces) const { + + const string matlabName = matlab_wrapper_name(matlabClassName); - // open destination wrapperFile - string wrapperFile = toolboxPath + "/" + matlabName + ".cpp"; - FileWriter file(wrapperFile, verbose_, "//"); - - // generate code - // - generateIncludes(file, name, includes); - cout << "Generate includes " << name << endl; - generateUsingNamespace(file, using_namespaces); + const string wrapFunctionName = matlabClassName + "_deconstructor_" + boost::lexical_cast(id); - file.oss << "void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[])" << endl; + file.oss << "void " << wrapFunctionName << "(int nargout, mxArray *out[], int nargin, const mxArray *in[])" << endl; file.oss << "{" << endl; + generateUsingNamespace(file, using_namespaces); + file.oss << " typedef boost::shared_ptr<" << cppClassName << "> Shared;" << endl; //Deconstructor takes 1 arg, the mxArray obj file.oss << " checkArguments(\"" << matlabName << "\",nargout,nargin," << "1" << ");" << endl; - file.oss << " delete_shared_ptr< " << cppClassName << " >(in[0],\"" << matlabClassName << "\");" << endl; + file.oss << " Shared *self = *reinterpret_cast(mxGetData(in[0]));\n"; + file.oss << " Collector_" << matlabClassName << "::iterator item;\n"; + file.oss << " item = collector_" << matlabClassName << ".find(self);\n"; + file.oss << " if(item != collector_" << matlabClassName << ".end()) {\n"; + file.oss << " delete self;\n"; + file.oss << " collector_" << matlabClassName << ".erase(item);\n"; + file.oss << " }\n"; file.oss << "}" << endl; - // close file - file.emit(true); + return wrapFunctionName; } /* ************************************************************************* */ diff --git a/wrap/Deconstructor.h b/wrap/Deconstructor.h index a5af4e327..1ef5b80b0 100644 --- a/wrap/Deconstructor.h +++ b/wrap/Deconstructor.h @@ -14,6 +14,7 @@ * @brief class describing a constructor + code generation * @author Frank Dellaert * @author Andrew Melim + * @author Richard Roberts **/ #pragma once @@ -34,7 +35,6 @@ struct Deconstructor { } // Then the instance variables are set directly by the Module deconstructor - ArgumentList args; std::string name; bool verbose_; @@ -46,15 +46,16 @@ struct Deconstructor { std::string matlab_wrapper_name(const std::string& className) const; /// m-file - void matlab_mfile(const std::string& toolboxPath, - const std::string& qualifiedMatlabName) const; + void proxy_fragment(FileWriter& file, + const std::string& wrapperName, + const std::string& qualifiedMatlabName, int id) const; /// cpp wrapper - void matlab_wrapper(const std::string& toolboxPath, + std::string wrapper_fragment(FileWriter& file, const std::string& cppClassName, const std::string& matlabClassName, - const std::vector& using_namespaces, - const std::vector& includes) const; + int id, + const std::vector& using_namespaces) const; }; } // \namespace wrap diff --git a/wrap/ForwardDeclaration.h b/wrap/ForwardDeclaration.h new file mode 100644 index 000000000..2c9b6fa0c --- /dev/null +++ b/wrap/ForwardDeclaration.h @@ -0,0 +1,32 @@ +/* ---------------------------------------------------------------------------- + + * 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 Class.h + * @brief describe the C++ class that is being wrapped + * @author Frank Dellaert + * @author Andrew Melim + * @author Richard Roberts + **/ + +#pragma once + +#include + +namespace wrap { + + struct ForwardDeclaration { + std::string name; + bool isVirtual; + ForwardDeclaration() : isVirtual(false) {} + }; + +} \ No newline at end of file diff --git a/wrap/Method.cpp b/wrap/Method.cpp index 60b02918f..f7ee5c71c 100644 --- a/wrap/Method.cpp +++ b/wrap/Method.cpp @@ -12,12 +12,14 @@ /** * @file Method.ccp * @author Frank Dellaert + * @author Richard Roberts **/ #include #include #include +#include #include "Method.h" #include "utilities.h" @@ -26,57 +28,108 @@ using namespace std; using namespace wrap; /* ************************************************************************* */ -void Method::matlab_mfile(const string& classPath) const { +void Method::addOverload(bool verbose, bool is_const, const std::string& name, + const ArgumentList& args, const ReturnValue& retVal) { + this->verbose_ = verbose; + this->is_const_ = is_const; + this->name = name; + this->argLists.push_back(args); + this->returnVals.push_back(retVal); +} - // open destination m-file - string wrapperFile = classPath + "/" + name + ".m"; - FileWriter file(wrapperFile, verbose_, "%"); +void Method::proxy_wrapper_fragments(FileWriter& proxyFile, FileWriter& wrapperFile, + const string& cppClassName, + const string& matlabClassName, + const string& wrapperName, + const vector& using_namespaces, + const TypeAttributesTable& typeAttributes, + vector& functionNames) const { - // generate code - string returnType = returnVal.matlab_returnType(); - file.oss << "% " << returnType << " = obj." << name << "(" << args.names() << ")" << endl; - file.oss << "function " << returnType << " = " << name << "(obj"; - if (args.size()) file.oss << "," << args.names(); - file.oss << ")" << endl; - file.oss << " error('need to compile " << name << ".cpp');" << endl; - file.oss << "end" << endl; + proxyFile.oss << " function varargout = " << name << "(this, varargin)\n"; - // close file - file.emit(false); + for(size_t overload = 0; overload < argLists.size(); ++overload) { + const ArgumentList& args = argLists[overload]; + const ReturnValue& returnVal = returnVals[overload]; + size_t nrArgs = args.size(); + + const int id = functionNames.size(); + + // Output proxy matlab code + + // check for number of arguments... + proxyFile.oss << " " << (overload==0?"":"else") << "if length(varargin) == " << nrArgs; + if (nrArgs>0) proxyFile.oss << " && "; + // ...and their types + bool first = true; + for(size_t i=0;i& using_namespaces, const std::vector& includes) const { - // open destination wrapperFile - string wrapperFile = classPath + "/" + name + ".cpp"; - FileWriter file(wrapperFile, verbose_, "//"); + int overload, + int id, + const vector& using_namespaces, + const TypeAttributesTable& typeAttributes) const { // generate code - // header - generateIncludes(file, className, includes); - generateUsingNamespace(file, using_namespaces); + const string wrapFunctionName = matlabClassName + "_" + name + "_" + boost::lexical_cast(id); + + const ArgumentList& args = argLists[overload]; + const ReturnValue& returnVal = returnVals[overload]; + + // call + file.oss << "void " << wrapFunctionName << "(int nargout, mxArray *out[], int nargin, const mxArray *in[])\n"; + // start + file.oss << "{\n"; + generateUsingNamespace(file, using_namespaces); if(returnVal.isPair) { if(returnVal.category1 == ReturnValue::CLASS) - file.oss << "typedef boost::shared_ptr<" << returnVal.qualifiedType1("::") << "> Shared" << returnVal.type1 << ";"<< endl; + file.oss << " typedef boost::shared_ptr<" << returnVal.qualifiedType1("::") << "> Shared" << returnVal.type1 << ";"<< endl; if(returnVal.category2 == ReturnValue::CLASS) - file.oss << "typedef boost::shared_ptr<" << returnVal.qualifiedType2("::") << "> Shared" << returnVal.type2 << ";"<< endl; + file.oss << " typedef boost::shared_ptr<" << returnVal.qualifiedType2("::") << "> Shared" << returnVal.type2 << ";"<< endl; } else if(returnVal.category1 == ReturnValue::CLASS) - file.oss << "typedef boost::shared_ptr<" << returnVal.qualifiedType1("::") << "> Shared" << returnVal.type1 << ";"<< endl; + file.oss << " typedef boost::shared_ptr<" << returnVal.qualifiedType1("::") << "> Shared" << returnVal.type1 << ";"<< endl; - file.oss << "typedef boost::shared_ptr<" << cppClassName << "> Shared;" << endl; - // call - file.oss << "void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[])\n"; - // start - file.oss << "{\n"; + file.oss << " typedef boost::shared_ptr<" << cppClassName << "> Shared;" << endl; // check arguments // extra argument obj -> nargin-1 is passed ! @@ -85,26 +138,21 @@ void Method::matlab_wrapper(const string& classPath, // get class pointer // example: shared_ptr = unwrap_shared_ptr< Test >(in[0], "Test"); - file.oss << " Shared obj = unwrap_shared_ptr<" << cppClassName << ">(in[0], \"" << cppClassName << "\");" << endl; + file.oss << " Shared obj = unwrap_shared_ptr<" << cppClassName << ">(in[0], \"ptr_" << matlabClassName << "\");" << endl; // unwrap arguments, see Argument.cpp args.matlab_unwrap(file,1); - // call method - // example: bool result = self->return_field(t); - file.oss << " "; + // call method and wrap result + // example: out[0]=wrap(self->return_field(t)); if (returnVal.type1!="void") - file.oss << returnVal.return_type(true,ReturnValue::pair) << " result = "; - file.oss << "obj->" << name << "(" << args.names() << ");\n"; - - // wrap result - // example: out[0]=wrap(result); - returnVal.wrap_result(file); + returnVal.wrap_result("obj->"+name+"("+args.names()+")", file, typeAttributes); + else + file.oss << " obj->"+name+"("+args.names()+");\n"; // finish file.oss << "}\n"; - // close file - file.emit(true); + return wrapFunctionName; } /* ************************************************************************* */ diff --git a/wrap/Method.h b/wrap/Method.h index bcfac82e3..c23fd7c3d 100644 --- a/wrap/Method.h +++ b/wrap/Method.h @@ -13,6 +13,7 @@ * @file Method.h * @brief describes and generates code for methods * @author Frank Dellaert + * @author Richard Roberts **/ #pragma once @@ -22,6 +23,7 @@ #include "Argument.h" #include "ReturnValue.h" +#include "TypeAttributesTable.h" namespace wrap { @@ -30,25 +32,37 @@ struct Method { /// Constructor creates empty object Method(bool verbose = true) : - verbose_(verbose) {} + verbose_(verbose), is_const_(false) {} // Then the instance variables are set directly by the Module constructor bool verbose_; bool is_const_; std::string name; - ArgumentList args; - ReturnValue returnVal; + std::vector argLists; + std::vector returnVals; + + // The first time this function is called, it initializes the class members + // with those in rhs, but in subsequent calls it adds additional argument + // lists as function overloads. + void addOverload(bool verbose, bool is_const, const std::string& name, + const ArgumentList& args, const ReturnValue& retVal); // MATLAB code generation // classPath is class directory, e.g., ../matlab/@Point2 + void proxy_wrapper_fragments(FileWriter& proxyFile, FileWriter& wrapperFile, + const std::string& cppClassName, const std::string& matlabClassName, + const std::string& wrapperName, const std::vector& using_namespaces, + const TypeAttributesTable& typeAttributes, + std::vector& functionNames) const; - void matlab_mfile(const std::string& classPath) const; ///< m-file - void matlab_wrapper(const std::string& classPath, - const std::string& className, +private: + std::string wrapper_fragment(FileWriter& file, const std::string& cppClassName, const std::string& matlabClassname, + int overload, + int id, const std::vector& using_namespaces, - const std::vector& includes) const; ///< cpp wrapper + const TypeAttributesTable& typeAttributes) const; ///< cpp wrapper }; } // \namespace wrap diff --git a/wrap/Module.cpp b/wrap/Module.cpp index 13adacc4c..a6fa3da20 100644 --- a/wrap/Module.cpp +++ b/wrap/Module.cpp @@ -1,389 +1,604 @@ -/* ---------------------------------------------------------------------------- - - * 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 Module.ccp - * @author Frank Dellaert - * @author Alex Cunningham - * @author Andrew Melim - **/ - -#include "Module.h" -#include "FileWriter.h" -#include "utilities.h" -#include "spirit_actors.h" - -//#define BOOST_SPIRIT_DEBUG -#include -#include -#include -#include -#include - -#include -#include - -using namespace std; -using namespace wrap; -using namespace BOOST_SPIRIT_CLASSIC_NS; -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. -// For example, str_p("const") parses the string "const", and the >> -// operator creates a sequence parser. The grammar below, composed of rules -// and with start rule [class_p], doubles as the specs for our interface files. -/* ************************************************************************* */ - -Module::Module(const string& interfacePath, - const string& moduleName, bool enable_verbose) : name(moduleName), verbose(enable_verbose) -{ - // these variables will be imperatively updated to gradually build [cls] - // The one with postfix 0 are used to reset the variables after parse. - ReturnValue retVal0, retVal; - Argument arg0, arg; - ArgumentList args0, args; - vector arg_dup; ///keep track of duplicates - Constructor constructor0(enable_verbose), constructor(enable_verbose); - //Deconstructor deconstructor0(enable_verbose), deconstructor(enable_verbose); - Method method0(enable_verbose), method(enable_verbose); - StaticMethod static_method0(enable_verbose), static_method(enable_verbose); - Class cls0(enable_verbose),cls(enable_verbose); - vector namespaces, /// current namespace tag - namespace_includes, /// current set of includes - namespaces_return, /// namespace for current return type - using_namespace_current; /// All namespaces from "using" declarations - string include_path = ""; - string class_name = ""; - const string null_str = ""; - - //---------------------------------------------------------------------------- - // Grammar with actions that build the Class object. Actions are - // defined within the square brackets [] and are executed whenever a - // rule is successfully parsed. Define BOOST_SPIRIT_DEBUG to debug. - // The grammar is allows a very restricted C++ header - // lexeme_d turns off white space skipping - // 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" | basisType_p); - - Rule eigenType_p = - (str_p("Vector") | "Matrix"); - - Rule className_p = (lexeme_d[upper_p >> *(alnum_p | '_')] - eigenType_p - keywords_p)[assign_a(class_name)]; - - Rule namespace_name_p = lexeme_d[lower_p >> *(alnum_p | '_')] - keywords_p; - - Rule namespace_arg_p = namespace_name_p[push_back_a(arg.namespaces)] >> str_p("::"); - - Rule argEigenType_p = - eigenType_p[assign_a(arg.type)] >> - !ch_p('*')[assign_a(arg.is_ptr,true)]; - - Rule eigenRef_p = - !str_p("const") [assign_a(arg.is_const,true)] >> - eigenType_p [assign_a(arg.type)] >> - 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)] >> - (ch_p('*')[assign_a(arg.is_ptr,true)] | ch_p('&')[assign_a(arg.is_ref,true)]); - - Rule name_p = lexeme_d[alpha_p >> *(alnum_p | '_')]; - - Rule argument_p = - ((basisType_p[assign_a(arg.type)] | argEigenType_p | eigenRef_p | classArg_p) - >> name_p[assign_a(arg.name)]) - [push_back_a(args, arg)] - [assign_a(arg,arg0)]; - - Rule argumentList_p = !argument_p >> * (',' >> argument_p); - - Rule constructor_p = - (className_p >> '(' >> argumentList_p >> ')' >> ';' >> !comments_p) - [push_back_a(constructor.args_list, args)] - [assign_a(args,args0)]; - //[assign_a(constructor.args,args)] - //[assign_a(constructor.name,cls.name)] - //[push_back_a(cls.constructors, constructor)] - //[assign_a(constructor,constructor0)]; - - Rule namespace_ret_p = namespace_name_p[push_back_a(namespaces_return)] >> str_p("::"); - - Rule returnType1_p = - (basisType_p[assign_a(retVal.type1)][assign_a(retVal.category1, ReturnValue::BASIS)]) | - ((*namespace_ret_p)[assign_a(retVal.namespaces1, namespaces_return)][clear_a(namespaces_return)] - >> (className_p[assign_a(retVal.type1)][assign_a(retVal.category1, ReturnValue::CLASS)]) >> - !ch_p('*')[assign_a(retVal.isPtr1,true)]) | - (eigenType_p[assign_a(retVal.type1)][assign_a(retVal.category1, ReturnValue::EIGEN)]); - - Rule returnType2_p = - (basisType_p[assign_a(retVal.type2)][assign_a(retVal.category2, ReturnValue::BASIS)]) | - ((*namespace_ret_p)[assign_a(retVal.namespaces2, namespaces_return)][clear_a(namespaces_return)] - >> (className_p[assign_a(retVal.type2)][assign_a(retVal.category2, ReturnValue::CLASS)]) >> - !ch_p('*') [assign_a(retVal.isPtr2,true)]) | - (eigenType_p[assign_a(retVal.type2)][assign_a(retVal.category2, ReturnValue::EIGEN)]); - - Rule pair_p = - (str_p("pair") >> '<' >> returnType1_p >> ',' >> returnType2_p >> '>') - [assign_a(retVal.isPair,true)]; - - Rule void_p = str_p("void")[assign_a(retVal.type1)]; - - Rule returnType_p = void_p | returnType1_p | pair_p; - - Rule methodName_p = lexeme_d[lower_p >> *(alnum_p | '_')]; - - Rule method_p = - (returnType_p >> methodName_p[assign_a(method.name)] >> - '(' >> argumentList_p >> ')' >> - !str_p("const")[assign_a(method.is_const_,true)] >> ';' >> *comments_p) - [assign_a(method.args,args)] - [assign_a(args,args0)] - [assign_a(method.returnVal,retVal)] - [assign_a(retVal,retVal0)] - [push_back_a(cls.methods, method)] - [assign_a(method,method0)]; - - Rule staticMethodName_p = lexeme_d[(upper_p | lower_p) >> *(alnum_p | '_')]; - - Rule static_method_p = - (str_p("static") >> returnType_p >> staticMethodName_p[assign_a(static_method.name)] >> - '(' >> argumentList_p >> ')' >> ';' >> *comments_p) - [assign_a(static_method.args,args)] - [assign_a(args,args0)] - [assign_a(static_method.returnVal,retVal)] - [assign_a(retVal,retVal0)] - [push_back_a(cls.static_methods, static_method)] - [assign_a(static_method,static_method0)]; - - Rule functions_p = constructor_p | method_p | static_method_p; - - Rule include_p = str_p("#include") >> ch_p('<') >> (*(anychar_p - '>'))[assign_a(include_path)] >> ch_p('>'); - - Rule class_p = - (!*include_p - >> str_p("class")[push_back_a(cls.includes, include_path)][assign_a(include_path, null_str)] - >> className_p[assign_a(cls.name)] - >> '{' - >> *(functions_p | comments_p) - >> str_p("};")) - [assign_a(constructor.name, cls.name)] - [assign_a(cls.constructor, constructor)] - [assign_a(cls.namespaces, namespaces)] - [assign_a(cls.using_namespaces, using_namespace_current)] - [append_a(cls.includes, namespace_includes)] - //[assign_a(deconstructor.name,cls.name)] - //[assign_a(cls.d, deconstructor)] - [push_back_a(classes,cls)] - //[assign_a(deconstructor,deconstructor0)] - [assign_a(constructor, constructor0)] - [assign_a(cls,cls0)]; - - Rule namespace_def_p = - (!*include_p - >> str_p("namespace")[push_back_a(namespace_includes, include_path)][assign_a(include_path, null_str)] - >> namespace_name_p[push_back_a(namespaces)] - >> ch_p('{') - >> *(class_p | namespace_def_p | comments_p) - >> str_p("}///\\namespace") // end namespace, avoid confusion with classes - >> !namespace_name_p) - [pop_a(namespaces)] - [pop_a(namespace_includes)]; - - Rule using_namespace_p = - str_p("using") >> str_p("namespace") - >> namespace_name_p[push_back_a(using_namespace_current)] >> ch_p(';'); - - Rule forward_declaration_p = - str_p("class") >> - (*(namespace_name_p >> str_p("::")) >> className_p)[push_back_a(forward_declarations)] - >> ch_p(';'); - - Rule module_content_p = comments_p | using_namespace_p | class_p | forward_declaration_p | namespace_def_p ; - - Rule module_p = *module_content_p >> !end_p; - - //---------------------------------------------------------------------------- - // for debugging, define BOOST_SPIRIT_DEBUG -# ifdef BOOST_SPIRIT_DEBUG - BOOST_SPIRIT_DEBUG_NODE(className_p); - BOOST_SPIRIT_DEBUG_NODE(classPtr_p); - BOOST_SPIRIT_DEBUG_NODE(classRef_p); - 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(constructor_p); - BOOST_SPIRIT_DEBUG_NODE(returnType1_p); - BOOST_SPIRIT_DEBUG_NODE(returnType2_p); - BOOST_SPIRIT_DEBUG_NODE(pair_p); - BOOST_SPIRIT_DEBUG_NODE(void_p); - BOOST_SPIRIT_DEBUG_NODE(returnType_p); - BOOST_SPIRIT_DEBUG_NODE(methodName_p); - BOOST_SPIRIT_DEBUG_NODE(method_p); - BOOST_SPIRIT_DEBUG_NODE(class_p); - BOOST_SPIRIT_DEBUG_NODE(namespace_def_p); - BOOST_SPIRIT_DEBUG_NODE(module_p); -# endif - //---------------------------------------------------------------------------- - - // read interface file - string interfaceFile = interfacePath + "/" + moduleName + ".h"; - string contents = file_contents(interfaceFile); - - // and parse contents - parse_info info = parse(contents.c_str(), module_p, space_p); - if(!info.full) { - printf("parsing stopped at \n%.20s\n",info.stop); - throw ParseFailed(info.length); - } -} - -/* ************************************************************************* */ -template -void verifyArguments(const vector& validArgs, const vector& vt) { - BOOST_FOREACH(const T& t, vt) { - BOOST_FOREACH(Argument arg, t.args) { - string fullType = arg.qualifiedType("::"); - if(find(validArgs.begin(), validArgs.end(), fullType) - == validArgs.end()) - throw DependencyMissing(fullType, t.name); - } - } -} - -/* ************************************************************************* */ -template -void verifyReturnTypes(const vector& validtypes, const vector& vt) { - BOOST_FOREACH(const T& t, vt) { - const ReturnValue& retval = t.returnVal; - if (find(validtypes.begin(), validtypes.end(), retval.qualifiedType1("::")) == validtypes.end()) - throw DependencyMissing(retval.qualifiedType1("::"), t.name); - if (retval.isPair && find(validtypes.begin(), validtypes.end(), retval.qualifiedType2("::")) == validtypes.end()) - throw DependencyMissing(retval.qualifiedType2("::"), t.name); - } -} - -/* ************************************************************************* */ -void Module::matlab_code(const string& mexCommand, const string& toolboxPath, - const string& mexExt, const string& headerPath,const string& mexFlags) const { - - fs::create_directories(toolboxPath); - - // create make m-file - string matlabMakeFileName = toolboxPath + "/make_" + name + ".m"; - FileWriter makeModuleMfile(matlabMakeFileName, verbose, "%"); - - // create the (actual) make file - string makeFileName = toolboxPath + "/Makefile"; - FileWriter makeModuleMakefile(makeFileName, verbose, "#"); - - makeModuleMfile.oss << "echo on" << endl << endl; - makeModuleMfile.oss << "toolboxpath = mfilename('fullpath');" << endl; - makeModuleMfile.oss << "delims = find(toolboxpath == '/' | toolboxpath == '\\');" << endl; - makeModuleMfile.oss << "toolboxpath = toolboxpath(1:(delims(end)-1));" << endl; - makeModuleMfile.oss << "clear delims" << endl; - makeModuleMfile.oss << "addpath(toolboxpath);" << endl << endl; - - makeModuleMakefile.oss << "\nMEX = " << mexCommand << "\n"; - makeModuleMakefile.oss << "MEXENDING = " << mexExt << "\n"; - makeModuleMakefile.oss << "PATH_TO_WRAP = " << headerPath << "\n"; - makeModuleMakefile.oss << "mex_flags = " << mexFlags << "\n\n"; - - // Dependency check list - vector validTypes = forward_declarations; - validTypes.push_back("void"); - validTypes.push_back("string"); - validTypes.push_back("int"); - validTypes.push_back("bool"); - validTypes.push_back("char"); - validTypes.push_back("unsigned char"); - validTypes.push_back("size_t"); - validTypes.push_back("double"); - validTypes.push_back("Vector"); - validTypes.push_back("Matrix"); - - // add 'all' to Makefile - makeModuleMakefile.oss << "all: "; - BOOST_FOREACH(Class cls, classes) { - makeModuleMakefile.oss << cls.qualifiedName() << " "; - //Create a list of parsed classes for dependency checking - validTypes.push_back(cls.qualifiedName("::")); - } - makeModuleMakefile.oss << "\n\n"; - - // generate proxy classes and wrappers - BOOST_FOREACH(Class cls, classes) { - // create directory if needed - string classPath = toolboxPath + "/@" + cls.qualifiedName(); - fs::create_directories(classPath); - - // create proxy class - string classFile = classPath + "/" + cls.qualifiedName() + ".m"; - cls.matlab_proxy(classFile); - - // verify all of the function arguments - //TODO:verifyArguments(validTypes, cls.constructor.args_list); - verifyArguments(validTypes, cls.static_methods); - verifyArguments(validTypes, cls.methods); - - // verify function return types - verifyReturnTypes(validTypes, cls.static_methods); - verifyReturnTypes(validTypes, cls.methods); - - // create constructor and method wrappers - cls.matlab_constructors(toolboxPath); - cls.matlab_static_methods(toolboxPath); - cls.matlab_methods(classPath); - - // create deconstructor - //cls.matlab_deconstructor(toolboxPath); - - // add lines to make m-file - makeModuleMfile.oss << "%% " << cls.qualifiedName() << endl; - makeModuleMfile.oss << "cd(toolboxpath)" << endl; - cls.matlab_make_fragment(makeModuleMfile, toolboxPath, mexFlags); - - // add section to the (actual) make file - makeModuleMakefile.oss << "# " << cls.qualifiedName() << endl; - cls.makefile_fragment(makeModuleMakefile); - } - - // finish make m-file - makeModuleMfile.oss << "cd(toolboxpath)" << endl << endl; - makeModuleMfile.oss << "echo off" << endl; - makeModuleMfile.emit(true); // By default, compare existing file first - - // make clean at end of Makefile - makeModuleMakefile.oss << "\n\nclean: \n"; - makeModuleMakefile.oss << "\trm -rf *.$(MEXENDING)\n"; - BOOST_FOREACH(Class cls, classes) - makeModuleMakefile.oss << "\trm -rf @" << cls.qualifiedName() << "/*.$(MEXENDING)\n"; - - // finish Makefile - makeModuleMakefile.oss << "\n" << endl; - makeModuleMakefile.emit(true); - } - -/* ************************************************************************* */ +/* ---------------------------------------------------------------------------- + + * 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 Module.ccp + * @author Frank Dellaert + * @author Alex Cunningham + * @author Andrew Melim + * @author Richard Roberts + **/ + +#include "Module.h" +#include "FileWriter.h" +#include "TypeAttributesTable.h" +#include "utilities.h" +#include "spirit_actors.h" + +//#define BOOST_SPIRIT_DEBUG +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include + +using namespace std; +using namespace wrap; +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. +// For example, str_p("const") parses the string "const", and the >> +// operator creates a sequence parser. The grammar below, composed of rules +// and with start rule [class_p], doubles as the specs for our interface files. +/* ************************************************************************* */ + +/* ************************************************************************* */ +void handle_possible_template(vector& classes, const Class& cls, const string& templateArgument, const vector >& instantiations) { + if(instantiations.empty()) { + classes.push_back(cls); + } else { + vector classInstantiations = cls.expandTemplate(templateArgument, instantiations); + BOOST_FOREACH(const Class& c, classInstantiations) { + classes.push_back(c); + } + } +} + +/* ************************************************************************* */ +Module::Module(const string& interfacePath, + const string& moduleName, bool enable_verbose) : name(moduleName), verbose(enable_verbose) +{ + // these variables will be imperatively updated to gradually build [cls] + // The one with postfix 0 are used to reset the variables after parse. + string methodName, methodName0; + bool isConst, isConst0 = false; + ReturnValue retVal0, retVal; + Argument arg0, arg; + ArgumentList args0, args; + vector arg_dup; ///keep track of duplicates + Constructor constructor0(enable_verbose), constructor(enable_verbose); + Deconstructor deconstructor0(enable_verbose), deconstructor(enable_verbose); + //Method method0(enable_verbose), method(enable_verbose); + StaticMethod static_method0(enable_verbose), static_method(enable_verbose); + Class cls0(enable_verbose),cls(enable_verbose); + ForwardDeclaration fwDec0, fwDec; + vector namespaces, /// current namespace tag + namespace_includes, /// current set of includes + namespaces_return, /// namespace for current return type + using_namespace_current; /// All namespaces from "using" declarations + string templateArgument; + vector templateInstantiationNamespace; + vector > templateInstantiations; + TemplateInstantiationTypedef singleInstantiation, singleInstantiation0; + string include_path = ""; + const string null_str = ""; + + //---------------------------------------------------------------------------- + // Grammar with actions that build the Class object. Actions are + // defined within the square brackets [] and are executed whenever a + // rule is successfully parsed. Define BOOST_SPIRIT_DEBUG to debug. + // The grammar is allows a very restricted C++ header + // lexeme_d turns off white space skipping + // 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" | basisType_p); + + Rule eigenType_p = + (str_p("Vector") | "Matrix"); + + Rule className_p = (lexeme_d[upper_p >> *(alnum_p | '_')] - eigenType_p - keywords_p); + + Rule namespace_name_p = lexeme_d[lower_p >> *(alnum_p | '_')] - keywords_p; + + Rule namespace_arg_p = namespace_name_p[push_back_a(arg.namespaces)] >> str_p("::"); + + Rule argEigenType_p = + eigenType_p[assign_a(arg.type)] >> + !ch_p('*')[assign_a(arg.is_ptr,true)]; + + Rule eigenRef_p = + !str_p("const") [assign_a(arg.is_const,true)] >> + eigenType_p [assign_a(arg.type)] >> + 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)] >> + (ch_p('*')[assign_a(arg.is_ptr,true)] | ch_p('&')[assign_a(arg.is_ref,true)]); + + Rule name_p = lexeme_d[alpha_p >> *(alnum_p | '_')]; + + Rule classParent_p = + *(namespace_name_p[push_back_a(cls.qualifiedParent)] >> str_p("::")) >> + className_p[push_back_a(cls.qualifiedParent)]; + + Rule templateInstantiation_p = + (*(namespace_name_p[push_back_a(templateInstantiationNamespace)] >> str_p("::")) >> + className_p[push_back_a(templateInstantiationNamespace)]) + [push_back_a(templateInstantiations, templateInstantiationNamespace)] + [clear_a(templateInstantiationNamespace)]; + + Rule templateInstantiations_p = + (str_p("template") >> + '<' >> name_p[assign_a(templateArgument)] >> '=' >> '{' >> + !(templateInstantiation_p >> *(',' >> templateInstantiation_p)) >> + '}' >> '>') + [push_back_a(cls.templateArgs, templateArgument)]; + + Rule templateSingleInstantiationArg_p = + (*(namespace_name_p[push_back_a(templateInstantiationNamespace)] >> str_p("::")) >> + className_p[push_back_a(templateInstantiationNamespace)]) + [push_back_a(singleInstantiation.typeList, templateInstantiationNamespace)] + [clear_a(templateInstantiationNamespace)]; + + Rule templateSingleInstantiation_p = + (str_p("typedef") >> + *(namespace_name_p[push_back_a(singleInstantiation.classNamespaces)] >> str_p("::")) >> + className_p[assign_a(singleInstantiation.className)] >> + '<' >> templateSingleInstantiationArg_p >> *(',' >> templateSingleInstantiationArg_p) >> + '>' >> + className_p[assign_a(singleInstantiation.name)] >> + ';') + [assign_a(singleInstantiation.namespaces, namespaces)] + [push_back_a(templateInstantiationTypedefs, singleInstantiation)] + [assign_a(singleInstantiation, singleInstantiation0)]; + + Rule templateList_p = + (str_p("template") >> + '<' >> name_p[push_back_a(cls.templateArgs)] >> *(',' >> name_p[push_back_a(cls.templateArgs)]) >> + '>'); + + Rule argument_p = + ((basisType_p[assign_a(arg.type)] | argEigenType_p | eigenRef_p | classArg_p) + >> name_p[assign_a(arg.name)]) + [push_back_a(args, arg)] + [assign_a(arg,arg0)]; + + Rule argumentList_p = !argument_p >> * (',' >> argument_p); + + Rule constructor_p = + (className_p >> '(' >> argumentList_p >> ')' >> ';' >> !comments_p) + [push_back_a(constructor.args_list, args)] + [assign_a(args,args0)]; + //[assign_a(constructor.args,args)] + //[assign_a(constructor.name,cls.name)] + //[push_back_a(cls.constructors, constructor)] + //[assign_a(constructor,constructor0)]; + + Rule namespace_ret_p = namespace_name_p[push_back_a(namespaces_return)] >> str_p("::"); + + Rule returnType1_p = + (basisType_p[assign_a(retVal.type1)][assign_a(retVal.category1, ReturnValue::BASIS)]) | + ((*namespace_ret_p)[assign_a(retVal.namespaces1, namespaces_return)][clear_a(namespaces_return)] + >> (className_p[assign_a(retVal.type1)][assign_a(retVal.category1, ReturnValue::CLASS)]) >> + !ch_p('*')[assign_a(retVal.isPtr1,true)]) | + (eigenType_p[assign_a(retVal.type1)][assign_a(retVal.category1, ReturnValue::EIGEN)]); + + Rule returnType2_p = + (basisType_p[assign_a(retVal.type2)][assign_a(retVal.category2, ReturnValue::BASIS)]) | + ((*namespace_ret_p)[assign_a(retVal.namespaces2, namespaces_return)][clear_a(namespaces_return)] + >> (className_p[assign_a(retVal.type2)][assign_a(retVal.category2, ReturnValue::CLASS)]) >> + !ch_p('*') [assign_a(retVal.isPtr2,true)]) | + (eigenType_p[assign_a(retVal.type2)][assign_a(retVal.category2, ReturnValue::EIGEN)]); + + Rule pair_p = + (str_p("pair") >> '<' >> returnType1_p >> ',' >> returnType2_p >> '>') + [assign_a(retVal.isPair,true)]; + + Rule void_p = str_p("void")[assign_a(retVal.type1)]; + + Rule returnType_p = void_p | returnType1_p | pair_p; + + Rule methodName_p = lexeme_d[lower_p >> *(alnum_p | '_')]; + + Rule method_p = + (returnType_p >> methodName_p[assign_a(methodName)] >> + '(' >> argumentList_p >> ')' >> + !str_p("const")[assign_a(isConst,true)] >> ';' >> *comments_p) + [bl::bind(&Method::addOverload, + bl::var(cls.methods)[bl::var(methodName)], + verbose, + bl::var(isConst), + bl::var(methodName), + bl::var(args), + bl::var(retVal))] + [assign_a(isConst,isConst0)] + [assign_a(methodName,methodName0)] + [assign_a(args,args0)] + [assign_a(retVal,retVal0)]; + + Rule staticMethodName_p = lexeme_d[(upper_p | lower_p) >> *(alnum_p | '_')]; + + Rule static_method_p = + (str_p("static") >> returnType_p >> staticMethodName_p[assign_a(methodName)] >> + '(' >> argumentList_p >> ')' >> ';' >> *comments_p) + [bl::bind(&StaticMethod::addOverload, + bl::var(cls.static_methods)[bl::var(methodName)], + verbose, + bl::var(methodName), + bl::var(args), + bl::var(retVal))] + [assign_a(methodName,methodName0)] + [assign_a(args,args0)] + [assign_a(retVal,retVal0)]; + + Rule functions_p = constructor_p | method_p | static_method_p; + + Rule include_p = str_p("#include") >> ch_p('<') >> (*(anychar_p - '>'))[assign_a(include_path)] >> ch_p('>'); + + Rule class_p = + (!*include_p + >> !(templateInstantiations_p | templateList_p) + >> !(str_p("virtual")[assign_a(cls.isVirtual, true)]) + >> str_p("class")[push_back_a(cls.includes, include_path)][assign_a(include_path, null_str)] + >> className_p[assign_a(cls.name)] + >> ((':' >> classParent_p >> '{') | '{') + >> *(functions_p | comments_p) + >> str_p("};")) + [assign_a(constructor.name, cls.name)] + [assign_a(cls.constructor, constructor)] + [assign_a(cls.namespaces, namespaces)] + [assign_a(cls.using_namespaces, using_namespace_current)] + [append_a(cls.includes, namespace_includes)] + [assign_a(deconstructor.name,cls.name)] + [assign_a(cls.deconstructor, deconstructor)] + [bl::bind(&handle_possible_template, bl::var(classes), bl::var(cls), bl::var(templateArgument), bl::var(templateInstantiations))] + [assign_a(deconstructor,deconstructor0)] + [assign_a(constructor, constructor0)] + [assign_a(cls,cls0)] + [clear_a(templateArgument)] + [clear_a(templateInstantiations)]; + + Rule namespace_def_p = + (!*include_p + >> str_p("namespace")[push_back_a(namespace_includes, include_path)][assign_a(include_path, null_str)] + >> namespace_name_p[push_back_a(namespaces)] + >> ch_p('{') + >> *(class_p | templateSingleInstantiation_p | namespace_def_p | comments_p) + >> str_p("}///\\namespace") // end namespace, avoid confusion with classes + >> !namespace_name_p) + [pop_a(namespaces)] + [pop_a(namespace_includes)]; + + Rule using_namespace_p = + str_p("using") >> str_p("namespace") + >> namespace_name_p[push_back_a(using_namespace_current)] >> ch_p(';'); + + 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)] + >> ch_p(';') + [push_back_a(forward_declarations, fwDec)] + [assign_a(fwDec, fwDec0)]; + + Rule module_content_p = comments_p | using_namespace_p | class_p | templateSingleInstantiation_p | forward_declaration_p | namespace_def_p ; + + Rule module_p = *module_content_p >> !end_p; + + //---------------------------------------------------------------------------- + // for debugging, define BOOST_SPIRIT_DEBUG +# ifdef BOOST_SPIRIT_DEBUG + BOOST_SPIRIT_DEBUG_NODE(className_p); + BOOST_SPIRIT_DEBUG_NODE(classPtr_p); + BOOST_SPIRIT_DEBUG_NODE(classRef_p); + 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(constructor_p); + BOOST_SPIRIT_DEBUG_NODE(returnType1_p); + BOOST_SPIRIT_DEBUG_NODE(returnType2_p); + BOOST_SPIRIT_DEBUG_NODE(pair_p); + BOOST_SPIRIT_DEBUG_NODE(void_p); + BOOST_SPIRIT_DEBUG_NODE(returnType_p); + BOOST_SPIRIT_DEBUG_NODE(methodName_p); + BOOST_SPIRIT_DEBUG_NODE(method_p); + BOOST_SPIRIT_DEBUG_NODE(class_p); + BOOST_SPIRIT_DEBUG_NODE(namespace_def_p); + BOOST_SPIRIT_DEBUG_NODE(module_p); +# endif + //---------------------------------------------------------------------------- + + // read interface file + string interfaceFile = interfacePath + "/" + moduleName + ".h"; + string contents = file_contents(interfaceFile); + + // and parse contents + parse_info info = parse(contents.c_str(), module_p, space_p); + if(!info.full) { + printf("parsing stopped at \n%.20s\n",info.stop); + throw ParseFailed((int)info.length); + } +} + +/* ************************************************************************* */ +template +void verifyArguments(const vector& validArgs, const map& vt) { + typedef typename map::value_type Name_Method; + BOOST_FOREACH(const Name_Method& name_method, vt) { + const T& t = name_method.second; + BOOST_FOREACH(const ArgumentList& argList, t.argLists) { + BOOST_FOREACH(Argument arg, argList) { + string fullType = arg.qualifiedType("::"); + if(find(validArgs.begin(), validArgs.end(), fullType) + == validArgs.end()) + throw DependencyMissing(fullType, t.name); + } + } + } +} + +/* ************************************************************************* */ +template +void verifyReturnTypes(const vector& validtypes, const map& vt) { + typedef typename map::value_type Name_Method; + BOOST_FOREACH(const Name_Method& name_method, vt) { + const T& t = name_method.second; + BOOST_FOREACH(const ReturnValue& retval, t.returnVals) { + if (find(validtypes.begin(), validtypes.end(), retval.qualifiedType1("::")) == validtypes.end()) + throw DependencyMissing(retval.qualifiedType1("::"), t.name); + if (retval.isPair && find(validtypes.begin(), validtypes.end(), retval.qualifiedType2("::")) == validtypes.end()) + throw DependencyMissing(retval.qualifiedType2("::"), t.name); + } + } +} + +/* ************************************************************************* */ +void Module::generateIncludes(FileWriter& file) const { + + // collect includes + vector all_includes; + BOOST_FOREACH(const Class& cls, classes) { + bool added_include = false; + BOOST_FOREACH(const string& s, cls.includes) { + if (!s.empty()) { + all_includes.push_back(s); + added_include = true; + } + } + if (!added_include) // add default include + all_includes.push_back(cls.name + ".h"); + } + + // sort and remove duplicates + sort(all_includes.begin(), all_includes.end()); + vector::const_iterator last_include = unique(all_includes.begin(), all_includes.end()); + vector::const_iterator it = all_includes.begin(); + // add includes to file + for (; it != last_include; ++it) + file.oss << "#include <" << *it << ">" << endl; + file.oss << "\n"; +} + +/* ************************************************************************* */ +void Module::matlab_code(const string& toolboxPath, const string& headerPath) const { + + fs::create_directories(toolboxPath); + + // create the unified .cpp switch file + const string wrapperName = name + "_wrapper"; + string wrapperFileName = toolboxPath + "/" + wrapperName + ".cpp"; + FileWriter wrapperFile(wrapperFileName, verbose, "//"); + vector functionNames; // Function names stored by index for switch + wrapperFile.oss << "#include \n"; + wrapperFile.oss << "#include \n"; + wrapperFile.oss << "#include \n"; + wrapperFile.oss << "\n"; + + // Expand templates - This is done first so that template instantiations are + // counted in the list of valid types, have their attributes and dependencies + // checked, etc. + vector expandedClasses = ExpandTypedefInstantiations(classes, templateInstantiationTypedefs); + + // Dependency check list + vector validTypes = GenerateValidTypes(expandedClasses, forward_declarations); + + // Check that all classes have been defined somewhere + BOOST_FOREACH(const Class& cls, expandedClasses) { + // verify all of the function arguments + //TODO:verifyArguments(validTypes, cls.constructor.args_list); + verifyArguments(validTypes, cls.static_methods); + verifyArguments(validTypes, cls.methods); + + // verify function return types + verifyReturnTypes(validTypes, cls.static_methods); + verifyReturnTypes(validTypes, cls.methods); + + // verify parents + if(!cls.qualifiedParent.empty() && std::find(validTypes.begin(), validTypes.end(), wrap::qualifiedName("::", cls.qualifiedParent)) == validTypes.end()) + throw DependencyMissing(wrap::qualifiedName("::", cls.qualifiedParent), cls.qualifiedName("::")); + } + + // Create type attributes table and check validity + TypeAttributesTable typeAttributes; + typeAttributes.addClasses(expandedClasses); + typeAttributes.addForwardDeclarations(forward_declarations); + typeAttributes.checkValidity(expandedClasses); + + // Generate includes while avoiding redundant includes + generateIncludes(wrapperFile); + + // create typedef classes - we put this at the top of the wrap file so that collectors and method arguments can use these typedefs + BOOST_FOREACH(const Class& cls, expandedClasses) { + if(!cls.typedefName.empty()) + wrapperFile.oss << cls.getTypedef() << "\n"; + } + wrapperFile.oss << "\n"; + + // Generate collectors and cleanup function to be called from mexAtExit + WriteCollectorsAndCleanupFcn(wrapperFile, name, expandedClasses); + + // generate RTTI registry (for returning derived-most types) + WriteRTTIRegistry(wrapperFile, name, expandedClasses); + + // create proxy class and wrapper code + BOOST_FOREACH(const Class& cls, expandedClasses) { + string classFile = toolboxPath + "/" + cls.qualifiedName() + ".m"; + cls.matlab_proxy(classFile, wrapperName, typeAttributes, wrapperFile, functionNames); + } + + // finish wrapper file + wrapperFile.oss << "\n"; + finish_wrapper(wrapperFile, functionNames); + + wrapperFile.emit(true); + } + +/* ************************************************************************* */ + void Module::finish_wrapper(FileWriter& file, const std::vector& functionNames) const { + file.oss << "void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[])\n"; + file.oss << "{\n"; + file.oss << " mstream mout;\n"; // Send stdout to MATLAB console, see matlab.h + file.oss << " std::streambuf *outbuf = std::cout.rdbuf(&mout);\n\n"; + file.oss << " if(!_RTTIRegister_" << name << "_done) {\n"; + file.oss << " _" << name << "_RTTIRegister();\n"; + file.oss << " _RTTIRegister_" << name << "_done = true;\n"; + file.oss << " }\n"; + file.oss << " int id = unwrap(in[0]);\n\n"; + file.oss << " switch(id) {\n"; + for(size_t id = 0; id < functionNames.size(); ++id) { + file.oss << " case " << id << ":\n"; + file.oss << " " << functionNames[id] << "(nargout, out, nargin-1, in+1);\n"; + file.oss << " break;\n"; + } + file.oss << " }\n"; + file.oss << "\n"; + file.oss << " std::cout.rdbuf(outbuf);\n"; // Restore cout, see matlab.h + file.oss << "}\n"; + } + +/* ************************************************************************* */ +vector Module::ExpandTypedefInstantiations(const vector& classes, const vector instantiations) { + + vector expandedClasses = classes; + + BOOST_FOREACH(const TemplateInstantiationTypedef& inst, instantiations) { + // Add the new class to the list + expandedClasses.push_back(inst.findAndExpand(classes)); + } + + // Remove all template classes + for(int i = 0; i < expandedClasses.size(); ++i) + if(!expandedClasses[size_t(i)].templateArgs.empty()) { + expandedClasses.erase(expandedClasses.begin() + size_t(i)); + -- i; + } + + return expandedClasses; +} + +/* ************************************************************************* */ +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("void"); + validTypes.push_back("string"); + validTypes.push_back("int"); + validTypes.push_back("bool"); + validTypes.push_back("char"); + validTypes.push_back("unsigned char"); + validTypes.push_back("size_t"); + validTypes.push_back("double"); + validTypes.push_back("Vector"); + validTypes.push_back("Matrix"); + //Create a list of parsed classes for dependency checking + BOOST_FOREACH(const Class& cls, classes) { + validTypes.push_back(cls.qualifiedName("::")); + } + + return validTypes; +} + +/* ************************************************************************* */ +void Module::WriteCollectorsAndCleanupFcn(FileWriter& wrapperFile, const std::string& moduleName, const std::vector& classes) { + // Generate all collectors + BOOST_FOREACH(const Class& cls, classes) { + const string matlabName = cls.qualifiedName(), cppName = cls.qualifiedName("::"); + wrapperFile.oss << "typedef std::set*> " + << "Collector_" << matlabName << ";\n"; + wrapperFile.oss << "static Collector_" << matlabName << + " collector_" << matlabName << ";\n"; + } + + // generate mexAtExit cleanup function + wrapperFile.oss << "\nvoid _deleteAllObjects()\n"; + wrapperFile.oss << "{\n"; + BOOST_FOREACH(const Class& cls, classes) { + const string matlabName = cls.qualifiedName(); + const string cppName = cls.qualifiedName("::"); + const string collectorType = "Collector_" + matlabName; + const string collectorName = "collector_" + matlabName; + wrapperFile.oss << " for(" << collectorType << "::iterator iter = " << collectorName << ".begin();\n"; + wrapperFile.oss << " iter != " << collectorName << ".end(); ) {\n"; + wrapperFile.oss << " delete *iter;\n"; + wrapperFile.oss << " " << collectorName << ".erase(iter++);\n"; + wrapperFile.oss << " }\n"; + } + wrapperFile.oss << "}\n\n"; +} + +/* ************************************************************************* */ +void Module::WriteRTTIRegistry(FileWriter& wrapperFile, const std::string& moduleName, const std::vector& classes) { + wrapperFile.oss << + "static bool _RTTIRegister_" << moduleName << "_done = false;\n" + "void _" << moduleName << "_RTTIRegister() {\n" + " std::map types;\n"; + BOOST_FOREACH(const Class& cls, classes) { + if(cls.isVirtual) + wrapperFile.oss << + " types.insert(std::make_pair(typeid(" << cls.qualifiedName("::") << ").name(), \"" << cls.qualifiedName() << "\"));\n"; + } + wrapperFile.oss << "\n"; + + wrapperFile.oss << + " mxArray *registry = mexGetVariable(\"global\", \"gtsamwrap_rttiRegistry\");\n" + " if(!registry)\n" + " registry = mxCreateStructMatrix(1, 1, 0, NULL);\n" + " typedef std::pair StringPair;\n" + " BOOST_FOREACH(const StringPair& rtti_matlab, types) {\n" + " int fieldId = mxAddField(registry, rtti_matlab.first.c_str());\n" + " if(fieldId < 0)\n" + " mexErrMsgTxt(\"gtsam wrap: Error indexing RTTI types, inheritance will not work correctly\");\n" + " mxArray *matlabName = mxCreateString(rtti_matlab.second.c_str());\n" + " mxSetFieldByNumber(registry, 0, fieldId, matlabName);\n" + " }\n" + " if(mexPutVariable(\"global\", \"gtsamwrap_rttiRegistry\", registry) != 0)\n" + " mexErrMsgTxt(\"gtsam wrap: Error indexing RTTI types, inheritance will not work correctly\");\n" + " mxDestroyArray(registry);\n" + "}\n" + "\n"; +} + +/* ************************************************************************* */ diff --git a/wrap/Module.h b/wrap/Module.h index 239aa20b0..403f2f32d 100644 --- a/wrap/Module.h +++ b/wrap/Module.h @@ -13,14 +13,18 @@ * @file Module.h * @brief describes module to be wrapped * @author Frank Dellaert + * @author Richard Roberts **/ #pragma once #include #include +#include #include "Class.h" +#include "TemplateInstantiationTypedef.h" +#include "ForwardDeclaration.h" namespace wrap { @@ -28,11 +32,13 @@ namespace wrap { * A module just has a name and a list of classes */ struct Module { + std::string name; ///< module name std::vector classes; ///< list of classes + std::vector templateInstantiationTypedefs; ///< list of template instantiations bool verbose; ///< verbose flag // std::vector using_namespaces; ///< all default namespaces - std::vector forward_declarations; + std::vector forward_declarations; /// constructor that parses interface file Module(const std::string& interfacePath, @@ -41,11 +47,18 @@ struct Module { /// MATLAB code generation: void matlab_code( - const std::string& mexCommand, const std::string& path, - const std::string& mexExt, - const std::string& headerPath, - const std::string& mexFlags) const; + const std::string& headerPath) const; + + void finish_wrapper(FileWriter& file, const std::vector& functionNames) const; + + void generateIncludes(FileWriter& file) const; + +private: + static std::vector ExpandTypedefInstantiations(const std::vector& classes, const std::vector instantiations); + static std::vector GenerateValidTypes(const std::vector& classes, const std::vector forwardDeclarations); + static void WriteCollectorsAndCleanupFcn(FileWriter& wrapperFile, const std::string& moduleName, const std::vector& classes); + static void WriteRTTIRegistry(FileWriter& wrapperFile, const std::string& moduleName, const std::vector& classes); }; } // \namespace wrap diff --git a/wrap/ReturnValue.cpp b/wrap/ReturnValue.cpp index 087a1c6ef..a3efb094e 100644 --- a/wrap/ReturnValue.cpp +++ b/wrap/ReturnValue.cpp @@ -4,6 +4,7 @@ * @date Dec 1, 2011 * @author Alex Cunningham * @author Andrew Melim + * @author Richard Roberts */ #include @@ -46,45 +47,78 @@ string ReturnValue::qualifiedType2(const string& delim) const { /* ************************************************************************* */ //TODO:Fix this -void ReturnValue::wrap_result(FileWriter& file) const { +void ReturnValue::wrap_result(const string& result, FileWriter& file, const TypeAttributesTable& typeAttributes) const { string cppType1 = qualifiedType1("::"), matlabType1 = qualifiedType1(); string cppType2 = qualifiedType2("::"), matlabType2 = qualifiedType2(); if (isPair) { // first return value in pair - if (isPtr1) {// if we already have a pointer - file.oss << " Shared" << type1 <<"* ret = new Shared" << type1 << "(result.first);" << endl; - file.oss << " out[0] = wrap_collect_shared_ptr(ret,\"" << matlabType1 << "\");\n"; - } - else if (category1 == ReturnValue::CLASS) { // if we are going to make one - file.oss << " Shared" << type1 << "* ret = new Shared" << type1 << "(new " << cppType1 << "(result.first));\n"; - file.oss << " out[0] = wrap_collect_shared_ptr(ret,\"" << matlabType1 << "\");\n"; - } - else // if basis type - file.oss << " out[0] = wrap< " << return_type(true,arg1) << " >(result.first);\n"; + if (category1 == ReturnValue::CLASS) { // if we are going to make one + string objCopy, ptrType; + ptrType = "Shared" + type1; + const bool isVirtual = typeAttributes.at(cppType1).isVirtual; + if(isVirtual) { + if(isPtr1) + objCopy = result + ".first"; + else + objCopy = result + ".first.clone()"; + } else { + if(isPtr1) + objCopy = result + ".first"; + else + objCopy = ptrType + "(new " + cppType1 + "(" + result + ".first))"; + } + file.oss << " out[0] = wrap_shared_ptr(" << objCopy << ",\"" << matlabType1 << "\", " << (isVirtual ? "true" : "false") << ");\n"; + } else if(isPtr1) { + file.oss << " Shared" << type1 <<"* ret = new Shared" << type1 << "(" << result << ".first);" << endl; + file.oss << " out[0] = wrap_shared_ptr(ret,\"" << matlabType1 << "\", false);\n"; + } else // if basis type + file.oss << " out[0] = wrap< " << return_type(true,arg1) << " >(" << result << ".first);\n"; // second return value in pair - if (isPtr2) {// if we already have a pointer - file.oss << " Shared" << type2 <<"* ret = new Shared" << type2 << "(result.second);" << endl; - file.oss << " out[1] = wrap_collect_shared_ptr(ret,\"" << matlabType2 << "\");\n"; - } - else if (category2 == ReturnValue::CLASS) { // if we are going to make one - file.oss << " Shared" << type2 << "* ret = new Shared" << type2 << "(new " << cppType2 << "(result.first));\n"; - file.oss << " out[0] = wrap_collect_shared_ptr(ret,\"" << matlabType2 << "\");\n"; - } - else - file.oss << " out[1] = wrap< " << return_type(true,arg2) << " >(result.second);\n"; - } - else if (isPtr1){ - file.oss << " Shared" << type1 <<"* ret = new Shared" << type1 << "(result);" << endl; - file.oss << " out[0] = wrap_collect_shared_ptr(ret,\"" << matlabType1 << "\");\n"; + if (category2 == ReturnValue::CLASS) { // if we are going to make one + string objCopy, ptrType; + ptrType = "Shared" + type2; + const bool isVirtual = typeAttributes.at(cppType2).isVirtual; + if(isVirtual) { + if(isPtr2) + objCopy = result + ".second"; + else + objCopy = result + ".second.clone()"; + } else { + if(isPtr2) + objCopy = result + ".second"; + else + objCopy = ptrType + "(new " + cppType2 + "(" + result + ".second))"; + } + file.oss << " out[0] = wrap_shared_ptr(" << objCopy << ",\"" << matlabType2 << "\", " << (isVirtual ? "true" : "false") << ");\n"; + } else if(isPtr2) { + file.oss << " Shared" << type2 <<"* ret = new Shared" << type2 << "(" << result << ".second);" << endl; + file.oss << " out[1] = wrap_shared_ptr(ret,\"" << matlabType2 << "\");\n"; + } else + file.oss << " out[1] = wrap< " << return_type(true,arg2) << " >(" << result << ".second);\n"; } else if (category1 == ReturnValue::CLASS){ - file.oss << " Shared" << type1 << "* ret = new Shared" << type1 << "(new " << cppType1 << "(result));\n"; - file.oss << " out[0] = wrap_collect_shared_ptr(ret,\"" << matlabType1 << "\");\n"; - } - else if (matlabType1!="void") - file.oss << " out[0] = wrap< " << return_type(true,arg1) << " >(result);\n"; + string objCopy, ptrType; + ptrType = "Shared" + type1; + const bool isVirtual = typeAttributes.at(cppType1).isVirtual; + if(isVirtual) { + if(isPtr1) + objCopy = result; + else + objCopy = result + ".clone()"; + } else { + if(isPtr1) + objCopy = result; + else + objCopy = ptrType + "(new " + cppType1 + "(" + result + "))"; + } + file.oss << " out[0] = wrap_shared_ptr(" << objCopy << ",\"" << matlabType1 << "\", " << (isVirtual ? "true" : "false") << ");\n"; + } else if(isPtr1) { + file.oss << " Shared" << type1 <<"* ret = new Shared" << type1 << "(" << result << ");" << endl; + file.oss << " out[0] = wrap_shared_ptr(ret,\"" << matlabType1 << "\");\n"; + } else if (matlabType1!="void") + file.oss << " out[0] = wrap< " << return_type(true,arg1) << " >(" << result << ");\n"; } /* ************************************************************************* */ diff --git a/wrap/ReturnValue.h b/wrap/ReturnValue.h index 859e00433..8ff5d712b 100644 --- a/wrap/ReturnValue.h +++ b/wrap/ReturnValue.h @@ -5,11 +5,14 @@ * * @date Dec 1, 2011 * @author Alex Cunningham + * @author Richard Roberts */ #include +#include #include "FileWriter.h" +#include "TypeAttributesTable.h" #pragma once @@ -47,7 +50,7 @@ struct ReturnValue { std::string matlab_returnType() const; - void wrap_result(FileWriter& file) const; + void wrap_result(const std::string& result, FileWriter& file, const TypeAttributesTable& typeAttributes) const; }; diff --git a/wrap/StaticMethod.cpp b/wrap/StaticMethod.cpp index a4fb3fbe8..19dcd375e 100644 --- a/wrap/StaticMethod.cpp +++ b/wrap/StaticMethod.cpp @@ -13,12 +13,14 @@ * @file StaticMethod.ccp * @author Frank Dellaert * @author Andrew Melim + * @author Richard Roberts **/ #include #include #include +#include #include "StaticMethod.h" #include "utilities.h" @@ -26,80 +28,131 @@ using namespace std; using namespace wrap; + /* ************************************************************************* */ -void StaticMethod::matlab_mfile(const string& toolboxPath, const string& className) const { +void StaticMethod::addOverload(bool verbose, const std::string& name, + const ArgumentList& args, const ReturnValue& retVal) { + this->verbose = verbose; + this->name = name; + this->argLists.push_back(args); + this->returnVals.push_back(retVal); +} - // open destination m-file - string full_name = className + "_" + name; - string wrapperFile = toolboxPath + "/" + full_name + ".m"; - FileWriter file(wrapperFile, verbose, "%"); +void StaticMethod::proxy_wrapper_fragments(FileWriter& proxyFile, FileWriter& wrapperFile, + const string& cppClassName, + const string& matlabClassName, + const string& wrapperName, + const vector& using_namespaces, + const TypeAttributesTable& typeAttributes, + vector& functionNames) const { - // generate code - string returnType = returnVal.matlab_returnType(); - file.oss << "function " << returnType << " = " << full_name << "("; - if (args.size()) file.oss << args.names(); - file.oss << ")" << endl; - file.oss << "% usage: x = " << full_name << "(" << args.names() << ")" << endl; - file.oss << " error('need to compile " << full_name << ".cpp');" << endl; - file.oss << "end" << endl; + string upperName = name; upperName[0] = std::toupper(upperName[0], std::locale()); - // close file - file.emit(true); + proxyFile.oss << " function varargout = " << upperName << "(varargin)\n"; + + for(size_t overload = 0; overload < argLists.size(); ++overload) { + const ArgumentList& args = argLists[overload]; + const ReturnValue& returnVal = returnVals[overload]; + size_t nrArgs = args.size(); + + const int id = functionNames.size(); + + // Output proxy matlab code + + // check for number of arguments... + proxyFile.oss << " " << (overload==0?"":"else") << "if length(varargin) == " << nrArgs; + if (nrArgs>0) proxyFile.oss << " && "; + // ...and their types + bool first = true; + for(size_t i=0;i& using_namespaces, - const vector& includes) const { - // open destination wrapperFile - string full_name = matlabClassName + "_" + name; - string wrapperFile = toolboxPath + "/" + full_name + ".cpp"; - FileWriter file(wrapperFile, verbose, "//"); +string StaticMethod::wrapper_fragment(FileWriter& file, + const string& cppClassName, + const string& matlabClassName, + int overload, + int id, + const vector& using_namespaces, + const TypeAttributesTable& typeAttributes) const { // generate code - // header - generateIncludes(file, className, includes); - generateUsingNamespace(file, using_namespaces); + const string wrapFunctionName = matlabClassName + "_" + name + "_" + boost::lexical_cast(id); + + const ArgumentList& args = argLists[overload]; + const ReturnValue& returnVal = returnVals[overload]; + + // call + file.oss << "void " << wrapFunctionName << "(int nargout, mxArray *out[], int nargin, const mxArray *in[])\n"; + // start + file.oss << "{\n"; + generateUsingNamespace(file, using_namespaces); if(returnVal.isPair) { - file.oss << "typedef boost::shared_ptr<" << returnVal.qualifiedType1("::") << "> Shared" << returnVal.type1 << ";"<< endl; - file.oss << "typedef boost::shared_ptr<" << returnVal.qualifiedType2("::") << "> Shared" << returnVal.type2 << ";"<< endl; + if(returnVal.category1 == ReturnValue::CLASS) + file.oss << " typedef boost::shared_ptr<" << returnVal.qualifiedType1("::") << "> Shared" << returnVal.type1 << ";"<< endl; + if(returnVal.category2 == ReturnValue::CLASS) + file.oss << " typedef boost::shared_ptr<" << returnVal.qualifiedType2("::") << "> Shared" << returnVal.type2 << ";"<< endl; } else - file.oss << "typedef boost::shared_ptr<" << returnVal.qualifiedType1("::") << "> Shared" << returnVal.type1 << ";"<< endl; + if(returnVal.category1 == ReturnValue::CLASS) + file.oss << " typedef boost::shared_ptr<" << returnVal.qualifiedType1("::") << "> Shared" << returnVal.type1 << ";"<< endl; - file.oss << "typedef boost::shared_ptr<" << cppClassName << "> Shared;" << endl; - // call - file.oss << "void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[])\n"; - // start - file.oss << "{\n"; + file.oss << " typedef boost::shared_ptr<" << cppClassName << "> Shared;" << endl; // check arguments // NOTE: for static functions, there is no object passed - file.oss << " checkArguments(\"" << full_name << "\",nargout,nargin," << args.size() << ");\n"; + file.oss << " checkArguments(\"" << matlabClassName << "." << name << "\",nargout,nargin," << args.size() << ");\n"; // unwrap arguments, see Argument.cpp args.matlab_unwrap(file,0); // We start at 0 because there is no self object file.oss << " "; - // call method with default type + // call method with default type and wrap result if (returnVal.type1!="void") - file.oss << returnVal.return_type(true,ReturnValue::pair) << " result = "; - file.oss << cppClassName << "::" << name << "(" << args.names() << ");\n"; - - // wrap result - // example: out[0]=wrap(result); - returnVal.wrap_result(file); + returnVal.wrap_result(cppClassName+"::"+name+"("+args.names()+")", file, typeAttributes); + else + file.oss << cppClassName+"::"+name+"("+args.names()+");\n"; // finish file.oss << "}\n"; - // close file - file.emit(true); + return wrapFunctionName; } /* ************************************************************************* */ diff --git a/wrap/StaticMethod.h b/wrap/StaticMethod.h index f9cc14af7..8951f965b 100644 --- a/wrap/StaticMethod.h +++ b/wrap/StaticMethod.h @@ -14,6 +14,7 @@ * @brief describes and generates code for static methods * @author Frank Dellaert * @author Alex Cunningham + * @author Richard Roberts **/ #pragma once @@ -23,6 +24,7 @@ #include "Argument.h" #include "ReturnValue.h" +#include "TypeAttributesTable.h" namespace wrap { @@ -36,20 +38,31 @@ struct StaticMethod { // Then the instance variables are set directly by the Module constructor bool verbose; std::string name; - ArgumentList args; - ReturnValue returnVal; + std::vector argLists; + std::vector returnVals; + + // The first time this function is called, it initializes the class members + // with those in rhs, but in subsequent calls it adds additional argument + // lists as function overloads. + void addOverload(bool verbose, const std::string& name, + const ArgumentList& args, const ReturnValue& retVal); // MATLAB code generation - // toolboxPath is the core toolbox directory, e.g., ../matlab - // NOTE: static functions are not inside the class, and - // are created with [ClassName]_[FunctionName]() format + // classPath is class directory, e.g., ../matlab/@Point2 + void proxy_wrapper_fragments(FileWriter& proxyFile, FileWriter& wrapperFile, + const std::string& cppClassName, const std::string& matlabClassName, + const std::string& wrapperName, const std::vector& using_namespaces, + const TypeAttributesTable& typeAttributes, + std::vector& functionNames) const; - void matlab_mfile(const std::string& toolboxPath, const std::string& className) const; ///< m-file - void matlab_wrapper(const std::string& toolboxPath, - const std::string& className, const std::string& matlabClassName, - const std::string& cppClassName, - const std::vector& using_namespaces, - const std::vector& includes) const; ///< cpp wrapper +private: + std::string wrapper_fragment(FileWriter& file, + const std::string& cppClassName, + const std::string& matlabClassname, + int overload, + int id, + const std::vector& using_namespaces, + const TypeAttributesTable& typeAttributes) const; ///< cpp wrapper }; } // \namespace wrap diff --git a/wrap/TemplateInstantiationTypedef.cpp b/wrap/TemplateInstantiationTypedef.cpp new file mode 100644 index 000000000..da1e8f616 --- /dev/null +++ b/wrap/TemplateInstantiationTypedef.cpp @@ -0,0 +1,61 @@ +/* ---------------------------------------------------------------------------- + + * 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 Class.cpp + * @author Frank Dellaert + * @author Andrew Melim + * @author Richard Roberts + **/ + +#include "TemplateInstantiationTypedef.h" + +#include "utilities.h" + +using namespace std; + +namespace wrap { + + Class TemplateInstantiationTypedef::findAndExpand(const vector& classes) const { + // Find matching class + std::vector::const_iterator clsIt = classes.end(); + for(std::vector::const_iterator it = classes.begin(); it != classes.end(); ++it) { + if(it->name == className && it->namespaces == classNamespaces && it->templateArgs.size() == typeList.size()) { + clsIt = it; + break; + } + } + + if(clsIt == classes.end()) + throw DependencyMissing(wrap::qualifiedName("::", classNamespaces, className), + "instantiation into typedef name " + wrap::qualifiedName("::", namespaces, name) + + ". Ensure that the typedef provides the correct number of template arguments."); + + // Instantiate it + Class classInst = *clsIt; + for(size_t i = 0; i < typeList.size(); ++i) + classInst = classInst.expandTemplate(classInst.templateArgs[i], typeList[i]); + + // Fix class properties + classInst.name = name; + classInst.templateArgs.clear(); + classInst.typedefName = clsIt->qualifiedName("::") + "<"; + if(typeList.size() > 0) + classInst.typedefName += wrap::qualifiedName("::", typeList[0]); + for(size_t i = 1; i < typeList.size(); ++i) + classInst.typedefName += (", " + wrap::qualifiedName("::", typeList[i])); + classInst.typedefName += ">"; + classInst.namespaces = namespaces; + + return classInst; + } + +} \ No newline at end of file diff --git a/wrap/TemplateInstantiationTypedef.h b/wrap/TemplateInstantiationTypedef.h new file mode 100644 index 000000000..192d35324 --- /dev/null +++ b/wrap/TemplateInstantiationTypedef.h @@ -0,0 +1,39 @@ +/* ---------------------------------------------------------------------------- + + * 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 Class.h + * @brief describe the C++ class that is being wrapped + * @author Frank Dellaert + * @author Andrew Melim + * @author Richard Roberts + **/ + +#pragma once + +#include +#include + +#include "Class.h" + +namespace wrap { + +struct TemplateInstantiationTypedef { + std::vector classNamespaces; + std::string className; + std::vector namespaces; + std::string name; + std::vector > typeList; + + Class findAndExpand(const std::vector& classes) const; +}; + +} \ No newline at end of file diff --git a/wrap/TypeAttributesTable.cpp b/wrap/TypeAttributesTable.cpp new file mode 100644 index 000000000..865015a6e --- /dev/null +++ b/wrap/TypeAttributesTable.cpp @@ -0,0 +1,58 @@ +/* ---------------------------------------------------------------------------- + + * 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 Class.cpp + * @author Frank Dellaert + * @author Andrew Melim + * @author Richard Roberts + **/ + +#include "TypeAttributesTable.h" +#include "Class.h" +#include "utilities.h" + +#include + +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("::")); + } + } + + /* ************************************************************************* */ + 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::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 + if(!cls.qualifiedParent.empty() && !at(wrap::qualifiedName("::", cls.qualifiedParent)).isVirtual) + throw AttributeError(wrap::qualifiedName("::", cls.qualifiedParent), + "Is the base class of " + cls.qualifiedName("::") + ", so needs to be declared virtual"); + } + } + +} \ No newline at end of file diff --git a/wrap/TypeAttributesTable.h b/wrap/TypeAttributesTable.h new file mode 100644 index 000000000..dea6d0bf5 --- /dev/null +++ b/wrap/TypeAttributesTable.h @@ -0,0 +1,55 @@ +/* ---------------------------------------------------------------------------- + + * 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 Class.h + * @brief describe the C++ class that is being wrapped + * @author Frank Dellaert + * @author Andrew Melim + * @author Richard Roberts + **/ + +#include +#include +#include + +#include "ForwardDeclaration.h" + +#pragma once + +namespace wrap { + + // Forward declarations + struct 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, + * and whether to try to convert it to a more derived type upon returning it. + */ +struct TypeAttributes { + bool isVirtual; + TypeAttributes() : isVirtual(false) {} + TypeAttributes(bool isVirtual) : isVirtual(isVirtual) {} +}; + +/** Map of type names to attributes. */ +class TypeAttributesTable : public std::map { +public: + TypeAttributesTable() {} + + void addClasses(const std::vector& classes); + void addForwardDeclarations(const std::vector& forwardDecls); + + void checkValidity(const std::vector& classes) const; +}; + +} \ No newline at end of file diff --git a/wrap/matlab.h b/wrap/matlab.h index 31e29c806..5b438f1a6 100644 --- a/wrap/matlab.h +++ b/wrap/matlab.h @@ -1,372 +1,426 @@ -/* ---------------------------------------------------------------------------- - - * 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 matlab.h - * @brief header file to be included in MATLAB wrappers - * @date 2008 - * @author Frank Dellaert - * - * wrapping and unwrapping is done using specialized templates, see - * http://www.cplusplus.com/doc/tutorial/templates.html - */ - -#include -#include - -using gtsam::Vector; -using gtsam::Matrix; - -extern "C" { -#include -} - -#include -#include -#include - -#include -#include -#include -#include -#include - -using namespace std; -using namespace boost; // not usual, but for conciseness of generated code - -// start GTSAM Specifics ///////////////////////////////////////////////// -// to enable Matrix and Vector constructor for SharedGaussian: -#define GTSAM_MAGIC_GAUSSIAN -// end GTSAM Specifics ///////////////////////////////////////////////// - -#if defined(__LP64__) || defined(_WIN64) -// 64-bit -#define mxUINT32OR64_CLASS mxUINT64_CLASS -#else -#define mxUINT32OR64_CLASS mxUINT32_CLASS -#endif - -//***************************************************************************** -// Utilities -//***************************************************************************** - -void error(const char* str) { - mexErrMsgIdAndTxt("wrap:error", str); -} - -mxArray *scalar(mxClassID classid) { - mwSize dims[1]; dims[0]=1; - return mxCreateNumericArray(1, dims, classid, mxREAL); -} - -void checkScalar(const mxArray* array, const char* str) { - int m = mxGetM(array), n = mxGetN(array); - if (m!=1 || n!=1) - mexErrMsgIdAndTxt("wrap: not a scalar in ", str); -} - -//***************************************************************************** -// Check arguments -//***************************************************************************** - -void checkArguments(const string& name, int nargout, int nargin, int expected) { - stringstream err; - err << name << " expects " << expected << " arguments, not " << nargin; - if (nargin!=expected) - error(err.str().c_str()); -} - -//***************************************************************************** -// wrapping C++ basis types in MATLAB arrays -//***************************************************************************** - -// default wrapping throws an error: only basis types are allowed in wrap -template -mxArray* wrap(Class& value) { - error("wrap internal error: attempted wrap of invalid type"); -} - -// specialization to string -// wraps into a character array -template<> -mxArray* wrap(string& value) { - return mxCreateString(value.c_str()); -} - -// specialization to char -template<> -mxArray* wrap(char& value) { - mxArray *result = scalar(mxUINT32OR64_CLASS); - *(char*)mxGetData(result) = value; - return result; -} - -// specialization to unsigned char -template<> -mxArray* wrap(unsigned char& value) { - mxArray *result = scalar(mxUINT32OR64_CLASS); - *(unsigned char*)mxGetData(result) = value; - return result; -} - -// specialization to bool -template<> -mxArray* wrap(bool& value) { - mxArray *result = scalar(mxUINT32OR64_CLASS); - *(bool*)mxGetData(result) = value; - return result; -} - -// specialization to size_t -template<> -mxArray* wrap(size_t& value) { - mxArray *result = scalar(mxUINT32OR64_CLASS); - *(size_t*)mxGetData(result) = value; - return result; -} - -// specialization to int -template<> -mxArray* wrap(int& value) { - mxArray *result = scalar(mxUINT32OR64_CLASS); - *(int*)mxGetData(result) = value; - return result; -} - -// specialization to double -> just double -template<> -mxArray* wrap(double& value) { - return mxCreateDoubleScalar(value); -} - -// wrap a const Eigen vector into a double vector -mxArray* wrap_Vector(const gtsam::Vector& v) { - int m = v.size(); - mxArray *result = mxCreateDoubleMatrix(m, 1, mxREAL); - double *data = mxGetPr(result); - for (int i=0;i double vector -template<> -mxArray* wrap(gtsam::Vector& v) { - return wrap_Vector(v); -} - -// const version -template<> -mxArray* wrap(const gtsam::Vector& v) { - return wrap_Vector(v); -} - -// wrap a const Eigen MATRIX into a double matrix -mxArray* wrap_Matrix(const gtsam::Matrix& A) { - int m = A.rows(), n = A.cols(); -#ifdef DEBUG_WRAP - mexPrintf("wrap_Matrix called with A = \n", m,n); - gtsam::print(A); -#endif - mxArray *result = mxCreateDoubleMatrix(m, n, mxREAL); - double *data = mxGetPr(result); - // converts from column-major to row-major - for (int j=0;j double matrix -template<> -mxArray* wrap(gtsam::Matrix& A) { - return wrap_Matrix(A); -} - -// const version -template<> -mxArray* wrap(const gtsam::Matrix& A) { - return wrap_Matrix(A); -} - -//***************************************************************************** -// unwrapping MATLAB arrays into C++ basis types -//***************************************************************************** - -// default unwrapping throws an error -// as wrap only supports passing a reference or one of the basic types -template -T unwrap(const mxArray* array) { - error("wrap internal error: attempted unwrap of invalid type"); -} - -// specialization to string -// expects a character array -// Warning: relies on mxChar==char -template<> -string unwrap(const mxArray* array) { - char *data = mxArrayToString(array); - if (data==NULL) error("unwrap: not a character array"); - string str(data); - mxFree(data); - return str; -} - -// Check for 64-bit, as Mathworks says mxGetScalar only good for 32 bit -template -T myGetScalar(const mxArray* array) { - switch (mxGetClassID(array)) { - case mxINT64_CLASS: - return (T) *(int64_t*) mxGetData(array); - case mxUINT64_CLASS: - return (T) *(uint64_t*) mxGetData(array); - default: - // hope for the best! - return (T) mxGetScalar(array); - } -} - -// specialization to bool -template<> -bool unwrap(const mxArray* array) { - checkScalar(array,"unwrap"); - return myGetScalar(array); -} - -// specialization to char -template<> -char unwrap(const mxArray* array) { - checkScalar(array,"unwrap"); - return myGetScalar(array); -} - -// specialization to unsigned char -template<> -unsigned char unwrap(const mxArray* array) { - checkScalar(array,"unwrap"); - return myGetScalar(array); -} - -// specialization to int -template<> -int unwrap(const mxArray* array) { - checkScalar(array,"unwrap"); - return myGetScalar(array); -} - -// specialization to size_t -template<> -size_t unwrap(const mxArray* array) { - checkScalar(array, "unwrap"); - return myGetScalar(array); -} - -// specialization to double -template<> -double unwrap(const mxArray* array) { - checkScalar(array,"unwrap"); - return myGetScalar(array); -} - -// specialization to Eigen vector -template<> -gtsam::Vector unwrap< gtsam::Vector >(const mxArray* array) { - int m = mxGetM(array), n = mxGetN(array); - if (mxIsDouble(array)==false || n!=1) error("unwrap: not a vector"); -#ifdef DEBUG_WRAP - mexPrintf("unwrap< gtsam::Vector > called with %dx%d argument\n", m,n); -#endif - double* data = (double*)mxGetData(array); - gtsam::Vector v(m); - for (int i=0;i -gtsam::Matrix unwrap< gtsam::Matrix >(const mxArray* array) { - if (mxIsDouble(array)==false) error("unwrap: not a matrix"); - int m = mxGetM(array), n = mxGetN(array); -#ifdef DEBUG_WRAP - mexPrintf("unwrap< gtsam::Matrix > called with %dx%d argument\n", m,n); -#endif - double* data = (double*)mxGetData(array); - gtsam::Matrix A(m,n); - // converts from row-major to column-major - for (int j=0;j -mxArray* wrap_shared_ptr(boost::shared_ptr< Class >* shared_ptr, const char *classname) { - mxArray* mxh = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL); - *reinterpret_cast**> (mxGetData(mxh)) = shared_ptr; - //return mxh; - return create_object(classname, mxh); -} - -template -mxArray* wrap_collect_shared_ptr(boost::shared_ptr< Class >* shared_ptr, const char *classname) { - mxArray* mxh = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL); - *reinterpret_cast**> (mxGetData(mxh)) = shared_ptr; - //return mxh; - return create_collect_object(classname, mxh); -} - -template -boost::shared_ptr unwrap_shared_ptr(const mxArray* obj, const string& className) { - - mxArray* mxh = mxGetProperty(obj,0,"self"); - if (mxGetClassID(mxh) != mxUINT32OR64_CLASS || mxIsComplex(mxh) - || mxGetM(mxh) != 1 || mxGetN(mxh) != 1) error( - "Parameter is not an Shared type."); - - boost::shared_ptr* spp = *reinterpret_cast**> (mxGetData(mxh)); - return *spp; -} +/* ---------------------------------------------------------------------------- + + * 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 matlab.h + * @brief header file to be included in MATLAB wrappers + * @date 2008 + * @author Frank Dellaert + * @author Alex Cunningham + * @author Andrew Melim + * @author Richard Roberts + * + * wrapping and unwrapping is done using specialized templates, see + * http://www.cplusplus.com/doc/tutorial/templates.html + */ + +#include +#include + +using gtsam::Vector; +using gtsam::Matrix; + +extern "C" { +#include +} + +#include +#include +#include + +#include +#include +#include +#include +#include +#include + +using namespace std; +using namespace boost; // not usual, but for conciseness of generated code + +// start GTSAM Specifics ///////////////////////////////////////////////// +// to enable Matrix and Vector constructor for SharedGaussian: +#define GTSAM_MAGIC_GAUSSIAN +// end GTSAM Specifics ///////////////////////////////////////////////// + +#if defined(__LP64__) || defined(_WIN64) +// 64-bit +#define mxUINT32OR64_CLASS mxUINT64_CLASS +#else +#define mxUINT32OR64_CLASS mxUINT32_CLASS +#endif + +// "Unique" key to signal calling the matlab object constructor with a raw pointer +// to a shared pointer of the same C++ object type as the MATLAB type. +// Also present in utilities.h +static const uint64_t ptr_constructor_key = + (uint64_t('G') << 56) | + (uint64_t('T') << 48) | + (uint64_t('S') << 40) | + (uint64_t('A') << 32) | + (uint64_t('M') << 24) | + (uint64_t('p') << 16) | + (uint64_t('t') << 8) | + (uint64_t('r')); + +//***************************************************************************** +// Utilities +//***************************************************************************** + +void error(const char* str) { + mexErrMsgIdAndTxt("wrap:error", str); +} + +mxArray *scalar(mxClassID classid) { + mwSize dims[1]; dims[0]=1; + return mxCreateNumericArray(1, dims, classid, mxREAL); +} + +void checkScalar(const mxArray* array, const char* str) { + int m = mxGetM(array), n = mxGetN(array); + if (m!=1 || n!=1) + mexErrMsgIdAndTxt("wrap: not a scalar in ", str); +} + +// Replacement streambuf for cout that writes to the MATLAB console +// Thanks to http://stackoverflow.com/a/249008 +class mstream : public std::streambuf { +protected: + virtual std::streamsize xsputn(const char *s, std::streamsize n) { + mexPrintf("%.*s",n,s); + return n; + } + virtual int overflow(int c = EOF) { + if (c != EOF) { + mexPrintf("%.1s",&c); + } + return 1; + } +}; + +//***************************************************************************** +// Check arguments +//***************************************************************************** + +void checkArguments(const string& name, int nargout, int nargin, int expected) { + stringstream err; + err << name << " expects " << expected << " arguments, not " << nargin; + if (nargin!=expected) + error(err.str().c_str()); +} + +//***************************************************************************** +// wrapping C++ basis types in MATLAB arrays +//***************************************************************************** + +// default wrapping throws an error: only basis types are allowed in wrap +template +mxArray* wrap(const Class& value) { + error("wrap internal error: attempted wrap of invalid type"); + return 0; +} + +// specialization to string +// wraps into a character array +template<> +mxArray* wrap(const string& value) { + return mxCreateString(value.c_str()); +} + +// specialization to char +template<> +mxArray* wrap(const char& value) { + mxArray *result = scalar(mxUINT32OR64_CLASS); + *(char*)mxGetData(result) = value; + return result; +} + +// specialization to unsigned char +template<> +mxArray* wrap(const unsigned char& value) { + mxArray *result = scalar(mxUINT32OR64_CLASS); + *(unsigned char*)mxGetData(result) = value; + return result; +} + +// specialization to bool +template<> +mxArray* wrap(const bool& value) { + mxArray *result = scalar(mxUINT32OR64_CLASS); + *(bool*)mxGetData(result) = value; + return result; +} + +// specialization to size_t +template<> +mxArray* wrap(const size_t& value) { + mxArray *result = scalar(mxUINT32OR64_CLASS); + *(size_t*)mxGetData(result) = value; + return result; +} + +// specialization to int +template<> +mxArray* wrap(const int& value) { + mxArray *result = scalar(mxUINT32OR64_CLASS); + *(int*)mxGetData(result) = value; + return result; +} + +// specialization to double -> just double +template<> +mxArray* wrap(const double& value) { + return mxCreateDoubleScalar(value); +} + +// wrap a const Eigen vector into a double vector +mxArray* wrap_Vector(const gtsam::Vector& v) { + int m = v.size(); + mxArray *result = mxCreateDoubleMatrix(m, 1, mxREAL); + double *data = mxGetPr(result); + for (int i=0;i double vector +template<> +mxArray* wrap(const gtsam::Vector& v) { + return wrap_Vector(v); +} + +// wrap a const Eigen MATRIX into a double matrix +mxArray* wrap_Matrix(const gtsam::Matrix& A) { + int m = A.rows(), n = A.cols(); +#ifdef DEBUG_WRAP + mexPrintf("wrap_Matrix called with A = \n", m,n); + gtsam::print(A); +#endif + mxArray *result = mxCreateDoubleMatrix(m, n, mxREAL); + double *data = mxGetPr(result); + // converts from column-major to row-major + for (int j=0;j double matrix +template<> +mxArray* wrap(const gtsam::Matrix& A) { + return wrap_Matrix(A); +} + +//***************************************************************************** +// unwrapping MATLAB arrays into C++ basis types +//***************************************************************************** + +// default unwrapping throws an error +// as wrap only supports passing a reference or one of the basic types +template +T unwrap(const mxArray* array) { + error("wrap internal error: attempted unwrap of invalid type"); +} + +// specialization to string +// expects a character array +// Warning: relies on mxChar==char +template<> +string unwrap(const mxArray* array) { + char *data = mxArrayToString(array); + if (data==NULL) error("unwrap: not a character array"); + string str(data); + mxFree(data); + return str; +} + +// Check for 64-bit, as Mathworks says mxGetScalar only good for 32 bit +template +T myGetScalar(const mxArray* array) { + switch (mxGetClassID(array)) { + case mxINT64_CLASS: + return (T) *(int64_t*) mxGetData(array); + case mxUINT64_CLASS: + return (T) *(uint64_t*) mxGetData(array); + default: + // hope for the best! + return (T) mxGetScalar(array); + } +} + +// specialization to bool +template<> +bool unwrap(const mxArray* array) { + checkScalar(array,"unwrap"); + return myGetScalar(array); +} + +// specialization to char +template<> +char unwrap(const mxArray* array) { + checkScalar(array,"unwrap"); + return myGetScalar(array); +} + +// specialization to unsigned char +template<> +unsigned char unwrap(const mxArray* array) { + checkScalar(array,"unwrap"); + return myGetScalar(array); +} + +// specialization to int +template<> +int unwrap(const mxArray* array) { + checkScalar(array,"unwrap"); + return myGetScalar(array); +} + +// specialization to size_t +template<> +size_t unwrap(const mxArray* array) { + checkScalar(array, "unwrap"); + return myGetScalar(array); +} + +// specialization to double +template<> +double unwrap(const mxArray* array) { + checkScalar(array,"unwrap"); + return myGetScalar(array); +} + +// specialization to Eigen vector +template<> +gtsam::Vector unwrap< gtsam::Vector >(const mxArray* array) { + int m = mxGetM(array), n = mxGetN(array); + if (mxIsDouble(array)==false || n!=1) error("unwrap: not a vector"); +#ifdef DEBUG_WRAP + mexPrintf("unwrap< gtsam::Vector > called with %dx%d argument\n", m,n); +#endif + double* data = (double*)mxGetData(array); + gtsam::Vector v(m); + for (int i=0;i +gtsam::Matrix unwrap< gtsam::Matrix >(const mxArray* array) { + if (mxIsDouble(array)==false) error("unwrap: not a matrix"); + int m = mxGetM(array), n = mxGetN(array); +#ifdef DEBUG_WRAP + mexPrintf("unwrap< gtsam::Matrix > called with %dx%d argument\n", m,n); +#endif + double* data = (double*)mxGetData(array); + gtsam::Matrix A(m,n); + // converts from row-major to column-major + for (int j=0;j(mxGetData(input[0])) = ptr_constructor_key; + // Second input argument is the pointer + input[1] = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL); + *reinterpret_cast(mxGetData(input[1])) = pointer; + // If the class is virtual, use the RTTI name to look up the derived matlab type + const char *derivedClassName; + if(isVirtual) { + const mxArray *rttiRegistry = mexGetVariablePtr("global", "gtsamwrap_rttiRegistry"); + if(!rttiRegistry) + mexErrMsgTxt( + "gtsam wrap: RTTI registry is missing - it could have been cleared from the workspace." + " You can issue 'clear all' to completely clear the workspace, and next time a wrapped object is" + " created the RTTI registry will be recreated."); + const mxArray *derivedNameMx = mxGetField(rttiRegistry, 0, rttiName); + if(!derivedNameMx) + mexErrMsgTxt(( + "gtsam wrap: The derived class type " + string(rttiName) + " was not found in the RTTI registry. " + "Try calling 'clear all' twice consecutively - we have seen things not get unloaded properly the " + "first time. If this does not work, this may indicate an inconsistency in your wrap interface file. " + "The most likely cause for this is that a base class was marked virtual in the wrap interface " + "definition header file for gtsam or for your module, but a derived type was returned by a C++ " + "function and that derived type was not marked virtual (or was not specified in the wrap interface " + "definition header at all).").c_str()); + size_t strLen = mxGetN(derivedNameMx); + char *buf = new char[strLen+1]; + if(mxGetString(derivedNameMx, buf, strLen+1)) + mexErrMsgTxt("gtsam wrap: Internal error reading RTTI table, try 'clear all' to clear your workspace and reinitialize the toolbox."); + derivedClassName = buf; + input[2] = mxCreateString("void"); + nargin = 3; + } else { + derivedClassName = classname.c_str(); + } + // Call special pointer constructor, which sets 'self' + mexCallMATLAB(1,&result, nargin, input, derivedClassName); + // Deallocate our memory + mxDestroyArray(input[0]); + mxDestroyArray(input[1]); + if(isVirtual) { + mxDestroyArray(input[2]); + delete[] derivedClassName; + } + return result; +} + +/* + When the user calls a method that returns a shared pointer, we create + an ObjectHandle from the shared_pointer and return it as a proxy + class to matlab. +*/ +template +mxArray* wrap_shared_ptr(boost::shared_ptr< Class > shared_ptr, const std::string& matlabName, bool isVirtual) { + // Create actual class object from out pointer + mxArray* result; + if(isVirtual) { + boost::shared_ptr void_ptr(shared_ptr); + result = create_object(matlabName, &void_ptr, isVirtual, typeid(*shared_ptr).name()); + } else { + boost::shared_ptr *heapPtr = new boost::shared_ptr(shared_ptr); + result = create_object(matlabName, heapPtr, isVirtual, ""); + } + return result; +} + +template +boost::shared_ptr unwrap_shared_ptr(const mxArray* obj, const string& propertyName) { + + mxArray* mxh = mxGetProperty(obj,0, propertyName.c_str()); + if (mxGetClassID(mxh) != mxUINT32OR64_CLASS || mxIsComplex(mxh) + || mxGetM(mxh) != 1 || mxGetN(mxh) != 1) error( + "Parameter is not an Shared type."); + + boost::shared_ptr* spp = *reinterpret_cast**> (mxGetData(mxh)); + return *spp; +} diff --git a/wrap/tests/expected/@Point2/Point2.m b/wrap/tests/expected/@Point2/Point2.m deleted file mode 100644 index 5cfd7fc61..000000000 --- a/wrap/tests/expected/@Point2/Point2.m +++ /dev/null @@ -1,22 +0,0 @@ -% automatically generated by wrap -classdef Point2 < handle - properties - self = 0 - end - methods - function obj = Point2(varargin) - if (nargin == 0), obj.self = new_Point2(0,0); end - if (nargin == 2 && isa(varargin{1},'double') && isa(varargin{2},'double')), obj.self = new_Point2(0,1,varargin{1},varargin{2}); end - if nargin ==14, new_Point2(varargin{1},0); end - if nargin ~= 13 && nargin ~= 14 && obj.self == 0, error('Point2 constructor failed'); end - end - function delete(obj) - if obj.self ~= 0 - new_Point2(obj.self); - obj.self = 0; - end - end - function display(obj), obj.print(''); end - function disp(obj), obj.display; end - end -end diff --git a/wrap/tests/expected/@Point2/argChar.cpp b/wrap/tests/expected/@Point2/argChar.cpp deleted file mode 100644 index d0e9a7a7a..000000000 --- a/wrap/tests/expected/@Point2/argChar.cpp +++ /dev/null @@ -1,11 +0,0 @@ -// automatically generated by wrap -#include -#include -typedef boost::shared_ptr Shared; -void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("argChar",nargout,nargin-1,1); - Shared obj = unwrap_shared_ptr(in[0], "Point2"); - char a = unwrap< char >(in[1]); - obj->argChar(a); -} diff --git a/wrap/tests/expected/@Point2/argChar.m b/wrap/tests/expected/@Point2/argChar.m deleted file mode 100644 index 6c935a1d6..000000000 --- a/wrap/tests/expected/@Point2/argChar.m +++ /dev/null @@ -1,4 +0,0 @@ -% result = obj.argChar(a) -function result = argChar(obj,a) - error('need to compile argChar.cpp'); -end diff --git a/wrap/tests/expected/@Point2/argUChar.cpp b/wrap/tests/expected/@Point2/argUChar.cpp deleted file mode 100644 index 06e62c36b..000000000 --- a/wrap/tests/expected/@Point2/argUChar.cpp +++ /dev/null @@ -1,11 +0,0 @@ -// automatically generated by wrap -#include -#include -typedef boost::shared_ptr Shared; -void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("argUChar",nargout,nargin-1,1); - Shared obj = unwrap_shared_ptr(in[0], "Point2"); - unsigned char a = unwrap< unsigned char >(in[1]); - obj->argUChar(a); -} diff --git a/wrap/tests/expected/@Point2/argUChar.m b/wrap/tests/expected/@Point2/argUChar.m deleted file mode 100644 index ea42a2b4f..000000000 --- a/wrap/tests/expected/@Point2/argUChar.m +++ /dev/null @@ -1,4 +0,0 @@ -% result = obj.argUChar(a) -function result = argUChar(obj,a) - error('need to compile argUChar.cpp'); -end diff --git a/wrap/tests/expected/@Point2/dim.cpp b/wrap/tests/expected/@Point2/dim.cpp deleted file mode 100644 index a7e938a16..000000000 --- a/wrap/tests/expected/@Point2/dim.cpp +++ /dev/null @@ -1,11 +0,0 @@ -// automatically generated by wrap -#include -#include -typedef boost::shared_ptr Shared; -void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("dim",nargout,nargin-1,0); - Shared obj = unwrap_shared_ptr(in[0], "Point2"); - int result = obj->dim(); - out[0] = wrap< int >(result); -} diff --git a/wrap/tests/expected/@Point2/dim.m b/wrap/tests/expected/@Point2/dim.m deleted file mode 100644 index 934e0b895..000000000 --- a/wrap/tests/expected/@Point2/dim.m +++ /dev/null @@ -1,4 +0,0 @@ -% result = obj.dim() -function result = dim(obj) - error('need to compile dim.cpp'); -end diff --git a/wrap/tests/expected/@Point2/returnChar.cpp b/wrap/tests/expected/@Point2/returnChar.cpp deleted file mode 100644 index ed6f34190..000000000 --- a/wrap/tests/expected/@Point2/returnChar.cpp +++ /dev/null @@ -1,11 +0,0 @@ -// automatically generated by wrap -#include -#include -typedef boost::shared_ptr Shared; -void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("returnChar",nargout,nargin-1,0); - Shared obj = unwrap_shared_ptr(in[0], "Point2"); - char result = obj->returnChar(); - out[0] = wrap< char >(result); -} diff --git a/wrap/tests/expected/@Point2/returnChar.m b/wrap/tests/expected/@Point2/returnChar.m deleted file mode 100644 index 8c3ceee35..000000000 --- a/wrap/tests/expected/@Point2/returnChar.m +++ /dev/null @@ -1,4 +0,0 @@ -% result = obj.returnChar() -function result = returnChar(obj) - error('need to compile returnChar.cpp'); -end diff --git a/wrap/tests/expected/@Point2/vectorConfusion.cpp b/wrap/tests/expected/@Point2/vectorConfusion.cpp deleted file mode 100644 index 3e2982803..000000000 --- a/wrap/tests/expected/@Point2/vectorConfusion.cpp +++ /dev/null @@ -1,13 +0,0 @@ -// automatically generated by wrap -#include -#include -typedef boost::shared_ptr SharedVectorNotEigen; -typedef boost::shared_ptr Shared; -void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("vectorConfusion",nargout,nargin-1,0); - Shared obj = unwrap_shared_ptr(in[0], "Point2"); - VectorNotEigen result = obj->vectorConfusion(); - SharedVectorNotEigen* ret = new SharedVectorNotEigen(new VectorNotEigen(result)); - out[0] = wrap_collect_shared_ptr(ret,"VectorNotEigen"); -} diff --git a/wrap/tests/expected/@Point2/vectorConfusion.m b/wrap/tests/expected/@Point2/vectorConfusion.m deleted file mode 100644 index 9966c930d..000000000 --- a/wrap/tests/expected/@Point2/vectorConfusion.m +++ /dev/null @@ -1,4 +0,0 @@ -% result = obj.vectorConfusion() -function result = vectorConfusion(obj) - error('need to compile vectorConfusion.cpp'); -end diff --git a/wrap/tests/expected/@Point2/x.cpp b/wrap/tests/expected/@Point2/x.cpp deleted file mode 100644 index 273eb7834..000000000 --- a/wrap/tests/expected/@Point2/x.cpp +++ /dev/null @@ -1,11 +0,0 @@ -// automatically generated by wrap -#include -#include -typedef boost::shared_ptr Shared; -void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("x",nargout,nargin-1,0); - Shared obj = unwrap_shared_ptr(in[0], "Point2"); - double result = obj->x(); - out[0] = wrap< double >(result); -} diff --git a/wrap/tests/expected/@Point2/x.m b/wrap/tests/expected/@Point2/x.m deleted file mode 100644 index 44f069872..000000000 --- a/wrap/tests/expected/@Point2/x.m +++ /dev/null @@ -1,4 +0,0 @@ -% result = obj.x() -function result = x(obj) - error('need to compile x.cpp'); -end diff --git a/wrap/tests/expected/@Point2/y.cpp b/wrap/tests/expected/@Point2/y.cpp deleted file mode 100644 index 44f824fb0..000000000 --- a/wrap/tests/expected/@Point2/y.cpp +++ /dev/null @@ -1,11 +0,0 @@ -// automatically generated by wrap -#include -#include -typedef boost::shared_ptr Shared; -void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("y",nargout,nargin-1,0); - Shared obj = unwrap_shared_ptr(in[0], "Point2"); - double result = obj->y(); - out[0] = wrap< double >(result); -} diff --git a/wrap/tests/expected/@Point2/y.m b/wrap/tests/expected/@Point2/y.m deleted file mode 100644 index 7971c1e33..000000000 --- a/wrap/tests/expected/@Point2/y.m +++ /dev/null @@ -1,4 +0,0 @@ -% result = obj.y() -function result = y(obj) - error('need to compile y.cpp'); -end diff --git a/wrap/tests/expected/@Point3/Point3.m b/wrap/tests/expected/@Point3/Point3.m deleted file mode 100644 index 81bd00a5a..000000000 --- a/wrap/tests/expected/@Point3/Point3.m +++ /dev/null @@ -1,21 +0,0 @@ -% automatically generated by wrap -classdef Point3 < handle - properties - self = 0 - end - methods - function obj = Point3(varargin) - if (nargin == 3 && isa(varargin{1},'double') && isa(varargin{2},'double') && isa(varargin{3},'double')), obj.self = new_Point3(0,0,varargin{1},varargin{2},varargin{3}); end - if nargin ==14, new_Point3(varargin{1},0); end - if nargin ~= 13 && nargin ~= 14 && obj.self == 0, error('Point3 constructor failed'); end - end - function delete(obj) - if obj.self ~= 0 - new_Point3(obj.self); - obj.self = 0; - end - end - function display(obj), obj.print(''); end - function disp(obj), obj.display; end - end -end diff --git a/wrap/tests/expected/@Point3/norm.cpp b/wrap/tests/expected/@Point3/norm.cpp deleted file mode 100644 index dd5c726ee..000000000 --- a/wrap/tests/expected/@Point3/norm.cpp +++ /dev/null @@ -1,12 +0,0 @@ -// automatically generated by wrap -#include -#include -using namespace geometry; -typedef boost::shared_ptr Shared; -void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("norm",nargout,nargin-1,0); - Shared obj = unwrap_shared_ptr(in[0], "Point3"); - double result = obj->norm(); - out[0] = wrap< double >(result); -} diff --git a/wrap/tests/expected/@Point3/norm.m b/wrap/tests/expected/@Point3/norm.m deleted file mode 100644 index ad925e85d..000000000 --- a/wrap/tests/expected/@Point3/norm.m +++ /dev/null @@ -1,4 +0,0 @@ -% result = obj.norm() -function result = norm(obj) - error('need to compile norm.cpp'); -end diff --git a/wrap/tests/expected/@Test/Test.m b/wrap/tests/expected/@Test/Test.m deleted file mode 100644 index 63914d2aa..000000000 --- a/wrap/tests/expected/@Test/Test.m +++ /dev/null @@ -1,22 +0,0 @@ -% automatically generated by wrap -classdef Test < handle - properties - self = 0 - end - methods - function obj = Test(varargin) - if (nargin == 0), obj.self = new_Test(0,0); end - if (nargin == 2 && isa(varargin{1},'double') && isa(varargin{2},'double')), obj.self = new_Test(0,1,varargin{1},varargin{2}); end - if nargin ==14, new_Test(varargin{1},0); end - if nargin ~= 13 && nargin ~= 14 && obj.self == 0, error('Test constructor failed'); end - end - function delete(obj) - if obj.self ~= 0 - new_Test(obj.self); - obj.self = 0; - end - end - function display(obj), obj.print(''); end - function disp(obj), obj.display; end - end -end diff --git a/wrap/tests/expected/@Test/arg_EigenConstRef.cpp b/wrap/tests/expected/@Test/arg_EigenConstRef.cpp deleted file mode 100644 index a6a384870..000000000 --- a/wrap/tests/expected/@Test/arg_EigenConstRef.cpp +++ /dev/null @@ -1,12 +0,0 @@ -// automatically generated by wrap -#include -#include -using namespace geometry; -typedef boost::shared_ptr Shared; -void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("arg_EigenConstRef",nargout,nargin-1,1); - Shared obj = unwrap_shared_ptr(in[0], "Test"); - Matrix& value = *unwrap_shared_ptr< Matrix >(in[1], "Matrix"); - obj->arg_EigenConstRef(value); -} diff --git a/wrap/tests/expected/@Test/arg_EigenConstRef.m b/wrap/tests/expected/@Test/arg_EigenConstRef.m deleted file mode 100644 index c348014c1..000000000 --- a/wrap/tests/expected/@Test/arg_EigenConstRef.m +++ /dev/null @@ -1,4 +0,0 @@ -% result = obj.arg_EigenConstRef(value) -function result = arg_EigenConstRef(obj,value) - error('need to compile arg_EigenConstRef.cpp'); -end diff --git a/wrap/tests/expected/@Test/create_MixedPtrs.cpp b/wrap/tests/expected/@Test/create_MixedPtrs.cpp deleted file mode 100644 index 21010eb0c..000000000 --- a/wrap/tests/expected/@Test/create_MixedPtrs.cpp +++ /dev/null @@ -1,17 +0,0 @@ -// automatically generated by wrap -#include -#include -using namespace geometry; -typedef boost::shared_ptr SharedTest; -typedef boost::shared_ptr SharedTest; -typedef boost::shared_ptr Shared; -void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("create_MixedPtrs",nargout,nargin-1,0); - Shared obj = unwrap_shared_ptr(in[0], "Test"); - pair< Test, SharedTest > result = obj->create_MixedPtrs(); - SharedTest* ret = new SharedTest(new Test(result.first)); - out[0] = wrap_collect_shared_ptr(ret,"Test"); - SharedTest* ret = new SharedTest(result.second); - out[1] = wrap_collect_shared_ptr(ret,"Test"); -} diff --git a/wrap/tests/expected/@Test/create_MixedPtrs.m b/wrap/tests/expected/@Test/create_MixedPtrs.m deleted file mode 100644 index 38a9f1d7e..000000000 --- a/wrap/tests/expected/@Test/create_MixedPtrs.m +++ /dev/null @@ -1,4 +0,0 @@ -% [first,second] = obj.create_MixedPtrs() -function [first,second] = create_MixedPtrs(obj) - error('need to compile create_MixedPtrs.cpp'); -end diff --git a/wrap/tests/expected/@Test/create_ptrs.cpp b/wrap/tests/expected/@Test/create_ptrs.cpp deleted file mode 100644 index b51c3f00e..000000000 --- a/wrap/tests/expected/@Test/create_ptrs.cpp +++ /dev/null @@ -1,17 +0,0 @@ -// automatically generated by wrap -#include -#include -using namespace geometry; -typedef boost::shared_ptr SharedTest; -typedef boost::shared_ptr SharedTest; -typedef boost::shared_ptr Shared; -void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("create_ptrs",nargout,nargin-1,0); - Shared obj = unwrap_shared_ptr(in[0], "Test"); - pair< SharedTest, SharedTest > result = obj->create_ptrs(); - SharedTest* ret = new SharedTest(result.first); - out[0] = wrap_collect_shared_ptr(ret,"Test"); - SharedTest* ret = new SharedTest(result.second); - out[1] = wrap_collect_shared_ptr(ret,"Test"); -} diff --git a/wrap/tests/expected/@Test/create_ptrs.m b/wrap/tests/expected/@Test/create_ptrs.m deleted file mode 100644 index 80c6781dc..000000000 --- a/wrap/tests/expected/@Test/create_ptrs.m +++ /dev/null @@ -1,4 +0,0 @@ -% [first,second] = obj.create_ptrs() -function [first,second] = create_ptrs(obj) - error('need to compile create_ptrs.cpp'); -end diff --git a/wrap/tests/expected/@Test/print.cpp b/wrap/tests/expected/@Test/print.cpp deleted file mode 100644 index 3cf9cd14d..000000000 --- a/wrap/tests/expected/@Test/print.cpp +++ /dev/null @@ -1,11 +0,0 @@ -// automatically generated by wrap -#include -#include -using namespace geometry; -typedef boost::shared_ptr Shared; -void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("print",nargout,nargin-1,0); - Shared obj = unwrap_shared_ptr(in[0], "Test"); - obj->print(); -} diff --git a/wrap/tests/expected/@Test/print.m b/wrap/tests/expected/@Test/print.m deleted file mode 100644 index ca6bf4769..000000000 --- a/wrap/tests/expected/@Test/print.m +++ /dev/null @@ -1,4 +0,0 @@ -% result = obj.print() -function result = print(obj) - error('need to compile print.cpp'); -end diff --git a/wrap/tests/expected/@Test/return_Point2Ptr.cpp b/wrap/tests/expected/@Test/return_Point2Ptr.cpp deleted file mode 100644 index 0d8650e84..000000000 --- a/wrap/tests/expected/@Test/return_Point2Ptr.cpp +++ /dev/null @@ -1,15 +0,0 @@ -// automatically generated by wrap -#include -#include -using namespace geometry; -typedef boost::shared_ptr SharedPoint2; -typedef boost::shared_ptr Shared; -void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("return_Point2Ptr",nargout,nargin-1,1); - Shared obj = unwrap_shared_ptr(in[0], "Test"); - bool value = unwrap< bool >(in[1]); - SharedPoint2 result = obj->return_Point2Ptr(value); - SharedPoint2* ret = new SharedPoint2(result); - out[0] = wrap_collect_shared_ptr(ret,"Point2"); -} diff --git a/wrap/tests/expected/@Test/return_Point2Ptr.m b/wrap/tests/expected/@Test/return_Point2Ptr.m deleted file mode 100644 index 84e586bc7..000000000 --- a/wrap/tests/expected/@Test/return_Point2Ptr.m +++ /dev/null @@ -1,4 +0,0 @@ -% result = obj.return_Point2Ptr(value) -function result = return_Point2Ptr(obj,value) - error('need to compile return_Point2Ptr.cpp'); -end diff --git a/wrap/tests/expected/@Test/return_Test.cpp b/wrap/tests/expected/@Test/return_Test.cpp deleted file mode 100644 index fb3ad822c..000000000 --- a/wrap/tests/expected/@Test/return_Test.cpp +++ /dev/null @@ -1,15 +0,0 @@ -// automatically generated by wrap -#include -#include -using namespace geometry; -typedef boost::shared_ptr SharedTest; -typedef boost::shared_ptr Shared; -void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("return_Test",nargout,nargin-1,1); - Shared obj = unwrap_shared_ptr(in[0], "Test"); - boost::shared_ptr value = unwrap_shared_ptr< Test >(in[1], "Test"); - Test result = obj->return_Test(value); - SharedTest* ret = new SharedTest(new Test(result)); - out[0] = wrap_collect_shared_ptr(ret,"Test"); -} diff --git a/wrap/tests/expected/@Test/return_Test.m b/wrap/tests/expected/@Test/return_Test.m deleted file mode 100644 index d1a2e440c..000000000 --- a/wrap/tests/expected/@Test/return_Test.m +++ /dev/null @@ -1,4 +0,0 @@ -% result = obj.return_Test(value) -function result = return_Test(obj,value) - error('need to compile return_Test.cpp'); -end diff --git a/wrap/tests/expected/@Test/return_TestPtr.cpp b/wrap/tests/expected/@Test/return_TestPtr.cpp deleted file mode 100644 index 06bc80269..000000000 --- a/wrap/tests/expected/@Test/return_TestPtr.cpp +++ /dev/null @@ -1,15 +0,0 @@ -// automatically generated by wrap -#include -#include -using namespace geometry; -typedef boost::shared_ptr SharedTest; -typedef boost::shared_ptr Shared; -void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("return_TestPtr",nargout,nargin-1,1); - Shared obj = unwrap_shared_ptr(in[0], "Test"); - boost::shared_ptr value = unwrap_shared_ptr< Test >(in[1], "Test"); - SharedTest result = obj->return_TestPtr(value); - SharedTest* ret = new SharedTest(result); - out[0] = wrap_collect_shared_ptr(ret,"Test"); -} diff --git a/wrap/tests/expected/@Test/return_TestPtr.m b/wrap/tests/expected/@Test/return_TestPtr.m deleted file mode 100644 index 937c85fcc..000000000 --- a/wrap/tests/expected/@Test/return_TestPtr.m +++ /dev/null @@ -1,4 +0,0 @@ -% result = obj.return_TestPtr(value) -function result = return_TestPtr(obj,value) - error('need to compile return_TestPtr.cpp'); -end diff --git a/wrap/tests/expected/@Test/return_bool.cpp b/wrap/tests/expected/@Test/return_bool.cpp deleted file mode 100644 index e570d8dc2..000000000 --- a/wrap/tests/expected/@Test/return_bool.cpp +++ /dev/null @@ -1,13 +0,0 @@ -// automatically generated by wrap -#include -#include -using namespace geometry; -typedef boost::shared_ptr Shared; -void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("return_bool",nargout,nargin-1,1); - Shared obj = unwrap_shared_ptr(in[0], "Test"); - bool value = unwrap< bool >(in[1]); - bool result = obj->return_bool(value); - out[0] = wrap< bool >(result); -} diff --git a/wrap/tests/expected/@Test/return_bool.m b/wrap/tests/expected/@Test/return_bool.m deleted file mode 100644 index 358cb9750..000000000 --- a/wrap/tests/expected/@Test/return_bool.m +++ /dev/null @@ -1,4 +0,0 @@ -% result = obj.return_bool(value) -function result = return_bool(obj,value) - error('need to compile return_bool.cpp'); -end diff --git a/wrap/tests/expected/@Test/return_double.cpp b/wrap/tests/expected/@Test/return_double.cpp deleted file mode 100644 index 4a6322a72..000000000 --- a/wrap/tests/expected/@Test/return_double.cpp +++ /dev/null @@ -1,13 +0,0 @@ -// automatically generated by wrap -#include -#include -using namespace geometry; -typedef boost::shared_ptr Shared; -void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("return_double",nargout,nargin-1,1); - Shared obj = unwrap_shared_ptr(in[0], "Test"); - double value = unwrap< double >(in[1]); - double result = obj->return_double(value); - out[0] = wrap< double >(result); -} diff --git a/wrap/tests/expected/@Test/return_double.m b/wrap/tests/expected/@Test/return_double.m deleted file mode 100644 index 681371f39..000000000 --- a/wrap/tests/expected/@Test/return_double.m +++ /dev/null @@ -1,4 +0,0 @@ -% result = obj.return_double(value) -function result = return_double(obj,value) - error('need to compile return_double.cpp'); -end diff --git a/wrap/tests/expected/@Test/return_field.cpp b/wrap/tests/expected/@Test/return_field.cpp deleted file mode 100644 index a631635e3..000000000 --- a/wrap/tests/expected/@Test/return_field.cpp +++ /dev/null @@ -1,13 +0,0 @@ -// automatically generated by wrap -#include -#include -using namespace geometry; -typedef boost::shared_ptr Shared; -void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("return_field",nargout,nargin-1,1); - Shared obj = unwrap_shared_ptr(in[0], "Test"); - Test& t = *unwrap_shared_ptr< Test >(in[1], "Test"); - bool result = obj->return_field(t); - out[0] = wrap< bool >(result); -} diff --git a/wrap/tests/expected/@Test/return_field.m b/wrap/tests/expected/@Test/return_field.m deleted file mode 100644 index e2894c381..000000000 --- a/wrap/tests/expected/@Test/return_field.m +++ /dev/null @@ -1,4 +0,0 @@ -% result = obj.return_field(t) -function result = return_field(obj,t) - error('need to compile return_field.cpp'); -end diff --git a/wrap/tests/expected/@Test/return_int.cpp b/wrap/tests/expected/@Test/return_int.cpp deleted file mode 100644 index f909405eb..000000000 --- a/wrap/tests/expected/@Test/return_int.cpp +++ /dev/null @@ -1,13 +0,0 @@ -// automatically generated by wrap -#include -#include -using namespace geometry; -typedef boost::shared_ptr Shared; -void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("return_int",nargout,nargin-1,1); - Shared obj = unwrap_shared_ptr(in[0], "Test"); - int value = unwrap< int >(in[1]); - int result = obj->return_int(value); - out[0] = wrap< int >(result); -} diff --git a/wrap/tests/expected/@Test/return_int.m b/wrap/tests/expected/@Test/return_int.m deleted file mode 100644 index 779e9feb2..000000000 --- a/wrap/tests/expected/@Test/return_int.m +++ /dev/null @@ -1,4 +0,0 @@ -% result = obj.return_int(value) -function result = return_int(obj,value) - error('need to compile return_int.cpp'); -end diff --git a/wrap/tests/expected/@Test/return_matrix1.cpp b/wrap/tests/expected/@Test/return_matrix1.cpp deleted file mode 100644 index 1cc75d3d4..000000000 --- a/wrap/tests/expected/@Test/return_matrix1.cpp +++ /dev/null @@ -1,13 +0,0 @@ -// automatically generated by wrap -#include -#include -using namespace geometry; -typedef boost::shared_ptr Shared; -void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("return_matrix1",nargout,nargin-1,1); - Shared obj = unwrap_shared_ptr(in[0], "Test"); - Matrix value = unwrap< Matrix >(in[1]); - Matrix result = obj->return_matrix1(value); - out[0] = wrap< Matrix >(result); -} diff --git a/wrap/tests/expected/@Test/return_matrix1.m b/wrap/tests/expected/@Test/return_matrix1.m deleted file mode 100644 index d6d9791f9..000000000 --- a/wrap/tests/expected/@Test/return_matrix1.m +++ /dev/null @@ -1,4 +0,0 @@ -% result = obj.return_matrix1(value) -function result = return_matrix1(obj,value) - error('need to compile return_matrix1.cpp'); -end diff --git a/wrap/tests/expected/@Test/return_matrix2.cpp b/wrap/tests/expected/@Test/return_matrix2.cpp deleted file mode 100644 index 10c9e8647..000000000 --- a/wrap/tests/expected/@Test/return_matrix2.cpp +++ /dev/null @@ -1,13 +0,0 @@ -// automatically generated by wrap -#include -#include -using namespace geometry; -typedef boost::shared_ptr Shared; -void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("return_matrix2",nargout,nargin-1,1); - Shared obj = unwrap_shared_ptr(in[0], "Test"); - Matrix value = unwrap< Matrix >(in[1]); - Matrix result = obj->return_matrix2(value); - out[0] = wrap< Matrix >(result); -} diff --git a/wrap/tests/expected/@Test/return_matrix2.m b/wrap/tests/expected/@Test/return_matrix2.m deleted file mode 100644 index 584b365b8..000000000 --- a/wrap/tests/expected/@Test/return_matrix2.m +++ /dev/null @@ -1,4 +0,0 @@ -% result = obj.return_matrix2(value) -function result = return_matrix2(obj,value) - error('need to compile return_matrix2.cpp'); -end diff --git a/wrap/tests/expected/@Test/return_pair.cpp b/wrap/tests/expected/@Test/return_pair.cpp deleted file mode 100644 index 0fc359df6..000000000 --- a/wrap/tests/expected/@Test/return_pair.cpp +++ /dev/null @@ -1,15 +0,0 @@ -// automatically generated by wrap -#include -#include -using namespace geometry; -typedef boost::shared_ptr Shared; -void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("return_pair",nargout,nargin-1,2); - Shared obj = unwrap_shared_ptr(in[0], "Test"); - Vector v = unwrap< Vector >(in[1]); - Matrix A = unwrap< Matrix >(in[2]); - pair< Vector, Matrix > result = obj->return_pair(v,A); - out[0] = wrap< Vector >(result.first); - out[1] = wrap< Matrix >(result.second); -} diff --git a/wrap/tests/expected/@Test/return_pair.m b/wrap/tests/expected/@Test/return_pair.m deleted file mode 100644 index 2e892210c..000000000 --- a/wrap/tests/expected/@Test/return_pair.m +++ /dev/null @@ -1,4 +0,0 @@ -% [first,second] = obj.return_pair(v,A) -function [first,second] = return_pair(obj,v,A) - error('need to compile return_pair.cpp'); -end diff --git a/wrap/tests/expected/@Test/return_ptrs.cpp b/wrap/tests/expected/@Test/return_ptrs.cpp deleted file mode 100644 index c6c6f9655..000000000 --- a/wrap/tests/expected/@Test/return_ptrs.cpp +++ /dev/null @@ -1,19 +0,0 @@ -// automatically generated by wrap -#include -#include -using namespace geometry; -typedef boost::shared_ptr SharedTest; -typedef boost::shared_ptr SharedTest; -typedef boost::shared_ptr Shared; -void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("return_ptrs",nargout,nargin-1,2); - Shared obj = unwrap_shared_ptr(in[0], "Test"); - boost::shared_ptr p1 = unwrap_shared_ptr< Test >(in[1], "Test"); - boost::shared_ptr p2 = unwrap_shared_ptr< Test >(in[2], "Test"); - pair< SharedTest, SharedTest > result = obj->return_ptrs(p1,p2); - SharedTest* ret = new SharedTest(result.first); - out[0] = wrap_collect_shared_ptr(ret,"Test"); - SharedTest* ret = new SharedTest(result.second); - out[1] = wrap_collect_shared_ptr(ret,"Test"); -} diff --git a/wrap/tests/expected/@Test/return_ptrs.m b/wrap/tests/expected/@Test/return_ptrs.m deleted file mode 100644 index a7af4b73c..000000000 --- a/wrap/tests/expected/@Test/return_ptrs.m +++ /dev/null @@ -1,4 +0,0 @@ -% [first,second] = obj.return_ptrs(p1,p2) -function [first,second] = return_ptrs(obj,p1,p2) - error('need to compile return_ptrs.cpp'); -end diff --git a/wrap/tests/expected/@Test/return_size_t.cpp b/wrap/tests/expected/@Test/return_size_t.cpp deleted file mode 100644 index 9a6fc8598..000000000 --- a/wrap/tests/expected/@Test/return_size_t.cpp +++ /dev/null @@ -1,13 +0,0 @@ -// automatically generated by wrap -#include -#include -using namespace geometry; -typedef boost::shared_ptr Shared; -void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("return_size_t",nargout,nargin-1,1); - Shared obj = unwrap_shared_ptr(in[0], "Test"); - size_t value = unwrap< size_t >(in[1]); - size_t result = obj->return_size_t(value); - out[0] = wrap< size_t >(result); -} diff --git a/wrap/tests/expected/@Test/return_size_t.m b/wrap/tests/expected/@Test/return_size_t.m deleted file mode 100644 index 2fae64028..000000000 --- a/wrap/tests/expected/@Test/return_size_t.m +++ /dev/null @@ -1,4 +0,0 @@ -% result = obj.return_size_t(value) -function result = return_size_t(obj,value) - error('need to compile return_size_t.cpp'); -end diff --git a/wrap/tests/expected/@Test/return_string.cpp b/wrap/tests/expected/@Test/return_string.cpp deleted file mode 100644 index 3253e62ed..000000000 --- a/wrap/tests/expected/@Test/return_string.cpp +++ /dev/null @@ -1,13 +0,0 @@ -// automatically generated by wrap -#include -#include -using namespace geometry; -typedef boost::shared_ptr Shared; -void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("return_string",nargout,nargin-1,1); - Shared obj = unwrap_shared_ptr(in[0], "Test"); - string value = unwrap< string >(in[1]); - string result = obj->return_string(value); - out[0] = wrap< string >(result); -} diff --git a/wrap/tests/expected/@Test/return_string.m b/wrap/tests/expected/@Test/return_string.m deleted file mode 100644 index 67fb5f10d..000000000 --- a/wrap/tests/expected/@Test/return_string.m +++ /dev/null @@ -1,4 +0,0 @@ -% result = obj.return_string(value) -function result = return_string(obj,value) - error('need to compile return_string.cpp'); -end diff --git a/wrap/tests/expected/@Test/return_vector1.cpp b/wrap/tests/expected/@Test/return_vector1.cpp deleted file mode 100644 index 48ecbb643..000000000 --- a/wrap/tests/expected/@Test/return_vector1.cpp +++ /dev/null @@ -1,13 +0,0 @@ -// automatically generated by wrap -#include -#include -using namespace geometry; -typedef boost::shared_ptr Shared; -void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("return_vector1",nargout,nargin-1,1); - Shared obj = unwrap_shared_ptr(in[0], "Test"); - Vector value = unwrap< Vector >(in[1]); - Vector result = obj->return_vector1(value); - out[0] = wrap< Vector >(result); -} diff --git a/wrap/tests/expected/@Test/return_vector1.m b/wrap/tests/expected/@Test/return_vector1.m deleted file mode 100644 index 461c51618..000000000 --- a/wrap/tests/expected/@Test/return_vector1.m +++ /dev/null @@ -1,4 +0,0 @@ -% result = obj.return_vector1(value) -function result = return_vector1(obj,value) - error('need to compile return_vector1.cpp'); -end diff --git a/wrap/tests/expected/@Test/return_vector2.cpp b/wrap/tests/expected/@Test/return_vector2.cpp deleted file mode 100644 index 984ba259c..000000000 --- a/wrap/tests/expected/@Test/return_vector2.cpp +++ /dev/null @@ -1,13 +0,0 @@ -// automatically generated by wrap -#include -#include -using namespace geometry; -typedef boost::shared_ptr Shared; -void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("return_vector2",nargout,nargin-1,1); - Shared obj = unwrap_shared_ptr(in[0], "Test"); - Vector value = unwrap< Vector >(in[1]); - Vector result = obj->return_vector2(value); - out[0] = wrap< Vector >(result); -} diff --git a/wrap/tests/expected/@Test/return_vector2.m b/wrap/tests/expected/@Test/return_vector2.m deleted file mode 100644 index f3c77dd85..000000000 --- a/wrap/tests/expected/@Test/return_vector2.m +++ /dev/null @@ -1,4 +0,0 @@ -% result = obj.return_vector2(value) -function result = return_vector2(obj,value) - error('need to compile return_vector2.cpp'); -end diff --git a/wrap/tests/expected/Makefile b/wrap/tests/expected/Makefile deleted file mode 100644 index 92dece353..000000000 --- a/wrap/tests/expected/Makefile +++ /dev/null @@ -1,94 +0,0 @@ -# automatically generated by wrap - -MEX = mex -MEXENDING = mexa64 -PATH_TO_WRAP = /not_really_a_real_path/borg/gtsam/wrap -mex_flags = -O5 - -all: Point2 Point3 Test - -# Point2 -new_Point2.$(MEXENDING): new_Point2.cpp $(PATH_TO_WRAP)/matlab.h - $(MEX) $(mex_flags) new_Point2.cpp -output new_Point2 -@Point2/x.$(MEXENDING): @Point2/x.cpp $(PATH_TO_WRAP)/matlab.h - $(MEX) $(mex_flags) @Point2/x.cpp -output @Point2/x -@Point2/y.$(MEXENDING): @Point2/y.cpp $(PATH_TO_WRAP)/matlab.h - $(MEX) $(mex_flags) @Point2/y.cpp -output @Point2/y -@Point2/dim.$(MEXENDING): @Point2/dim.cpp $(PATH_TO_WRAP)/matlab.h - $(MEX) $(mex_flags) @Point2/dim.cpp -output @Point2/dim -@Point2/returnChar.$(MEXENDING): @Point2/returnChar.cpp $(PATH_TO_WRAP)/matlab.h - $(MEX) $(mex_flags) @Point2/returnChar.cpp -output @Point2/returnChar -@Point2/argChar.$(MEXENDING): @Point2/argChar.cpp $(PATH_TO_WRAP)/matlab.h - $(MEX) $(mex_flags) @Point2/argChar.cpp -output @Point2/argChar -@Point2/argUChar.$(MEXENDING): @Point2/argUChar.cpp $(PATH_TO_WRAP)/matlab.h - $(MEX) $(mex_flags) @Point2/argUChar.cpp -output @Point2/argUChar -@Point2/vectorConfusion.$(MEXENDING): @Point2/vectorConfusion.cpp $(PATH_TO_WRAP)/matlab.h - $(MEX) $(mex_flags) @Point2/vectorConfusion.cpp -output @Point2/vectorConfusion - -Point2: new_Point2.$(MEXENDING) @Point2/x.$(MEXENDING) @Point2/y.$(MEXENDING) @Point2/dim.$(MEXENDING) @Point2/returnChar.$(MEXENDING) @Point2/argChar.$(MEXENDING) @Point2/argUChar.$(MEXENDING) @Point2/vectorConfusion.$(MEXENDING) - -# Point3 -new_Point3.$(MEXENDING): new_Point3.cpp $(PATH_TO_WRAP)/matlab.h - $(MEX) $(mex_flags) new_Point3.cpp -output new_Point3 -Point3_staticFunction.$(MEXENDING): Point3_staticFunction.cpp $(PATH_TO_WRAP)/matlab.h - $(MEX) $(mex_flags) Point3_staticFunction.cpp -output Point3_staticFunction -Point3_StaticFunctionRet.$(MEXENDING): Point3_StaticFunctionRet.cpp $(PATH_TO_WRAP)/matlab.h - $(MEX) $(mex_flags) Point3_StaticFunctionRet.cpp -output Point3_StaticFunctionRet -@Point3/norm.$(MEXENDING): @Point3/norm.cpp $(PATH_TO_WRAP)/matlab.h - $(MEX) $(mex_flags) @Point3/norm.cpp -output @Point3/norm - -Point3: new_Point3.$(MEXENDING) Point3_staticFunction.$(MEXENDING) Point3_StaticFunctionRet.$(MEXENDING) @Point3/norm.$(MEXENDING) - -# Test -new_Test.$(MEXENDING): new_Test.cpp $(PATH_TO_WRAP)/matlab.h - $(MEX) $(mex_flags) new_Test.cpp -output new_Test -@Test/return_pair.$(MEXENDING): @Test/return_pair.cpp $(PATH_TO_WRAP)/matlab.h - $(MEX) $(mex_flags) @Test/return_pair.cpp -output @Test/return_pair -@Test/return_bool.$(MEXENDING): @Test/return_bool.cpp $(PATH_TO_WRAP)/matlab.h - $(MEX) $(mex_flags) @Test/return_bool.cpp -output @Test/return_bool -@Test/return_size_t.$(MEXENDING): @Test/return_size_t.cpp $(PATH_TO_WRAP)/matlab.h - $(MEX) $(mex_flags) @Test/return_size_t.cpp -output @Test/return_size_t -@Test/return_int.$(MEXENDING): @Test/return_int.cpp $(PATH_TO_WRAP)/matlab.h - $(MEX) $(mex_flags) @Test/return_int.cpp -output @Test/return_int -@Test/return_double.$(MEXENDING): @Test/return_double.cpp $(PATH_TO_WRAP)/matlab.h - $(MEX) $(mex_flags) @Test/return_double.cpp -output @Test/return_double -@Test/return_string.$(MEXENDING): @Test/return_string.cpp $(PATH_TO_WRAP)/matlab.h - $(MEX) $(mex_flags) @Test/return_string.cpp -output @Test/return_string -@Test/return_vector1.$(MEXENDING): @Test/return_vector1.cpp $(PATH_TO_WRAP)/matlab.h - $(MEX) $(mex_flags) @Test/return_vector1.cpp -output @Test/return_vector1 -@Test/return_matrix1.$(MEXENDING): @Test/return_matrix1.cpp $(PATH_TO_WRAP)/matlab.h - $(MEX) $(mex_flags) @Test/return_matrix1.cpp -output @Test/return_matrix1 -@Test/return_vector2.$(MEXENDING): @Test/return_vector2.cpp $(PATH_TO_WRAP)/matlab.h - $(MEX) $(mex_flags) @Test/return_vector2.cpp -output @Test/return_vector2 -@Test/return_matrix2.$(MEXENDING): @Test/return_matrix2.cpp $(PATH_TO_WRAP)/matlab.h - $(MEX) $(mex_flags) @Test/return_matrix2.cpp -output @Test/return_matrix2 -@Test/arg_EigenConstRef.$(MEXENDING): @Test/arg_EigenConstRef.cpp $(PATH_TO_WRAP)/matlab.h - $(MEX) $(mex_flags) @Test/arg_EigenConstRef.cpp -output @Test/arg_EigenConstRef -@Test/return_field.$(MEXENDING): @Test/return_field.cpp $(PATH_TO_WRAP)/matlab.h - $(MEX) $(mex_flags) @Test/return_field.cpp -output @Test/return_field -@Test/return_TestPtr.$(MEXENDING): @Test/return_TestPtr.cpp $(PATH_TO_WRAP)/matlab.h - $(MEX) $(mex_flags) @Test/return_TestPtr.cpp -output @Test/return_TestPtr -@Test/return_Test.$(MEXENDING): @Test/return_Test.cpp $(PATH_TO_WRAP)/matlab.h - $(MEX) $(mex_flags) @Test/return_Test.cpp -output @Test/return_Test -@Test/return_Point2Ptr.$(MEXENDING): @Test/return_Point2Ptr.cpp $(PATH_TO_WRAP)/matlab.h - $(MEX) $(mex_flags) @Test/return_Point2Ptr.cpp -output @Test/return_Point2Ptr -@Test/create_ptrs.$(MEXENDING): @Test/create_ptrs.cpp $(PATH_TO_WRAP)/matlab.h - $(MEX) $(mex_flags) @Test/create_ptrs.cpp -output @Test/create_ptrs -@Test/create_MixedPtrs.$(MEXENDING): @Test/create_MixedPtrs.cpp $(PATH_TO_WRAP)/matlab.h - $(MEX) $(mex_flags) @Test/create_MixedPtrs.cpp -output @Test/create_MixedPtrs -@Test/return_ptrs.$(MEXENDING): @Test/return_ptrs.cpp $(PATH_TO_WRAP)/matlab.h - $(MEX) $(mex_flags) @Test/return_ptrs.cpp -output @Test/return_ptrs -@Test/print.$(MEXENDING): @Test/print.cpp $(PATH_TO_WRAP)/matlab.h - $(MEX) $(mex_flags) @Test/print.cpp -output @Test/print - -Test: new_Test.$(MEXENDING) @Test/return_pair.$(MEXENDING) @Test/return_bool.$(MEXENDING) @Test/return_size_t.$(MEXENDING) @Test/return_int.$(MEXENDING) @Test/return_double.$(MEXENDING) @Test/return_string.$(MEXENDING) @Test/return_vector1.$(MEXENDING) @Test/return_matrix1.$(MEXENDING) @Test/return_vector2.$(MEXENDING) @Test/return_matrix2.$(MEXENDING) @Test/arg_EigenConstRef.$(MEXENDING) @Test/return_field.$(MEXENDING) @Test/return_TestPtr.$(MEXENDING) @Test/return_Test.$(MEXENDING) @Test/return_Point2Ptr.$(MEXENDING) @Test/create_ptrs.$(MEXENDING) @Test/create_MixedPtrs.$(MEXENDING) @Test/return_ptrs.$(MEXENDING) @Test/print.$(MEXENDING) - - - -clean: - rm -rf *.$(MEXENDING) - rm -rf @Point2/*.$(MEXENDING) - rm -rf @Point3/*.$(MEXENDING) - rm -rf @Test/*.$(MEXENDING) - - diff --git a/wrap/tests/expected/Point2.m b/wrap/tests/expected/Point2.m new file mode 100644 index 000000000..f23e15eb4 --- /dev/null +++ b/wrap/tests/expected/Point2.m @@ -0,0 +1,89 @@ +% automatically generated by wrap +classdef Point2 < handle + properties + ptr_Point2 = 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 Point2 constructor'); + end + obj.ptr_Point2 = my_ptr; + end + + function delete(obj) + geometry_wrapper(3, obj.ptr_Point2); + end + + function display(obj), obj.print(''); end + + function disp(obj), obj.display; end + + function varargout = argChar(this, varargin) + if length(varargin) == 1 && isa(varargin{1},'char') + geometry_wrapper(4, this, varargin{:}); + else + error('Arguments do not match any overload of function Point2.argChar'); + end + end + + function varargout = argUChar(this, varargin) + if length(varargin) == 1 && isa(varargin{1},'char') + geometry_wrapper(5, this, varargin{:}); + else + error('Arguments do not match any overload of function Point2.argUChar'); + end + end + + function varargout = dim(this, varargin) + if length(varargin) == 0 + varargout{1} = geometry_wrapper(6, this, varargin{:}); + else + error('Arguments do not match any overload of function Point2.dim'); + end + end + + function varargout = returnChar(this, varargin) + if length(varargin) == 0 + varargout{1} = geometry_wrapper(7, this, varargin{:}); + else + error('Arguments do not match any overload of function Point2.returnChar'); + end + end + + function varargout = vectorConfusion(this, varargin) + if length(varargin) == 0 + varargout{1} = geometry_wrapper(8, this, varargin{:}); + else + error('Arguments do not match any overload of function Point2.vectorConfusion'); + end + end + + function varargout = x(this, varargin) + if length(varargin) == 0 + varargout{1} = geometry_wrapper(9, this, varargin{:}); + else + error('Arguments do not match any overload of function Point2.x'); + end + end + + function varargout = y(this, varargin) + if length(varargin) == 0 + varargout{1} = geometry_wrapper(10, this, varargin{:}); + else + error('Arguments do not match any overload of function Point2.y'); + end + end + + end + + methods(Static = true) + end +end diff --git a/wrap/tests/expected/Point3.m b/wrap/tests/expected/Point3.m new file mode 100644 index 000000000..773ebefc0 --- /dev/null +++ b/wrap/tests/expected/Point3.m @@ -0,0 +1,55 @@ +% automatically generated by wrap +classdef Point3 < handle + properties + ptr_Point3 = 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 Point3 constructor'); + end + obj.ptr_Point3 = my_ptr; + end + + function delete(obj) + geometry_wrapper(13, obj.ptr_Point3); + end + + function display(obj), obj.print(''); end + + function disp(obj), obj.display; end + + function varargout = norm(this, varargin) + if length(varargin) == 0 + varargout{1} = geometry_wrapper(14, this, varargin{:}); + else + error('Arguments do not match any overload of function Point3.norm'); + end + end + + end + + methods(Static = true) + function varargout = StaticFunctionRet(varargin) + if length(varargin) == 1 && isa(varargin{1},'double') + varargout{1} = geometry_wrapper(15, varargin{:}); + else + error('Arguments do not match any overload of function Point3.StaticFunctionRet'); + end + end + + function varargout = StaticFunction(varargin) + if length(varargin) == 0 + varargout{1} = geometry_wrapper(16, varargin{:}); + else + error('Arguments do not match any overload of function Point3.StaticFunction'); + end + end + + end +end diff --git a/wrap/tests/expected/Point3_StaticFunctionRet.cpp b/wrap/tests/expected/Point3_StaticFunctionRet.cpp deleted file mode 100644 index 696af326a..000000000 --- a/wrap/tests/expected/Point3_StaticFunctionRet.cpp +++ /dev/null @@ -1,14 +0,0 @@ -// automatically generated by wrap -#include -#include -using namespace geometry; -typedef boost::shared_ptr SharedPoint3; -typedef boost::shared_ptr Shared; -void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("Point3_StaticFunctionRet",nargout,nargin,1); - double z = unwrap< double >(in[0]); - Point3 result = Point3::StaticFunctionRet(z); - SharedPoint3* ret = new SharedPoint3(new Point3(result)); - out[0] = wrap_collect_shared_ptr(ret,"Point3"); -} diff --git a/wrap/tests/expected/Point3_StaticFunctionRet.m b/wrap/tests/expected/Point3_StaticFunctionRet.m deleted file mode 100644 index bdfd32b4b..000000000 --- a/wrap/tests/expected/Point3_StaticFunctionRet.m +++ /dev/null @@ -1,5 +0,0 @@ -% automatically generated by wrap -function result = Point3_StaticFunctionRet(z) -% usage: x = Point3_StaticFunctionRet(z) - error('need to compile Point3_StaticFunctionRet.cpp'); -end diff --git a/wrap/tests/expected/Point3_staticFunction.cpp b/wrap/tests/expected/Point3_staticFunction.cpp deleted file mode 100644 index f25c8f4ea..000000000 --- a/wrap/tests/expected/Point3_staticFunction.cpp +++ /dev/null @@ -1,12 +0,0 @@ -// automatically generated by wrap -#include -#include -using namespace geometry; -typedef boost::shared_ptr Shareddouble; -typedef boost::shared_ptr Shared; -void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("Point3_staticFunction",nargout,nargin,0); - double result = Point3::staticFunction(); - out[0] = wrap< double >(result); -} diff --git a/wrap/tests/expected/Point3_staticFunction.m b/wrap/tests/expected/Point3_staticFunction.m deleted file mode 100644 index 23885f71e..000000000 --- a/wrap/tests/expected/Point3_staticFunction.m +++ /dev/null @@ -1,5 +0,0 @@ -% automatically generated by wrap -function result = Point3_staticFunction() -% usage: x = Point3_staticFunction() - error('need to compile Point3_staticFunction.cpp'); -end diff --git a/wrap/tests/expected/Test.m b/wrap/tests/expected/Test.m new file mode 100644 index 000000000..f36c8eb30 --- /dev/null +++ b/wrap/tests/expected/Test.m @@ -0,0 +1,185 @@ +% automatically generated by wrap +classdef Test < handle + properties + ptr_Test = 0 + end + methods + function obj = Test(varargin) + if nargin == 2 && isa(varargin{1}, 'uint64') && varargin{1} == uint64(5139824614673773682) + my_ptr = varargin{2}; + geometry_wrapper(17, my_ptr); + elseif nargin == 0 + my_ptr = geometry_wrapper(18); + elseif nargin == 2 && isa(varargin{1},'double') && isa(varargin{2},'double') + my_ptr = geometry_wrapper(19, varargin{1}, varargin{2}); + else + error('Arguments do not match any overload of Test constructor'); + end + obj.ptr_Test = my_ptr; + end + + function delete(obj) + geometry_wrapper(20, obj.ptr_Test); + end + + function display(obj), obj.print(''); end + + function disp(obj), obj.display; end + + function varargout = arg_EigenConstRef(this, varargin) + if length(varargin) == 1 && isa(varargin{1},'double') + geometry_wrapper(21, this, varargin{:}); + else + error('Arguments do not match any overload of function Test.arg_EigenConstRef'); + end + end + + function varargout = create_MixedPtrs(this, varargin) + if length(varargin) == 0 + [ varargout{1} varargout{2} ] = geometry_wrapper(22, this, varargin{:}); + else + error('Arguments do not match any overload of function Test.create_MixedPtrs'); + end + end + + function varargout = create_ptrs(this, varargin) + if length(varargin) == 0 + [ varargout{1} varargout{2} ] = geometry_wrapper(23, this, varargin{:}); + else + error('Arguments do not match any overload of function Test.create_ptrs'); + end + end + + function varargout = print(this, varargin) + if length(varargin) == 0 + geometry_wrapper(24, this, varargin{:}); + else + error('Arguments do not match any overload of function Test.print'); + end + end + + function varargout = return_Point2Ptr(this, varargin) + if length(varargin) == 1 && isa(varargin{1},'logical') + varargout{1} = geometry_wrapper(25, this, varargin{:}); + else + error('Arguments do not match any overload of function Test.return_Point2Ptr'); + end + end + + function varargout = return_Test(this, varargin) + if length(varargin) == 1 && isa(varargin{1},'Test') + varargout{1} = geometry_wrapper(26, this, varargin{:}); + else + error('Arguments do not match any overload of function Test.return_Test'); + end + end + + function varargout = return_TestPtr(this, varargin) + if length(varargin) == 1 && isa(varargin{1},'Test') + varargout{1} = geometry_wrapper(27, this, varargin{:}); + else + error('Arguments do not match any overload of function Test.return_TestPtr'); + end + end + + function varargout = return_bool(this, varargin) + if length(varargin) == 1 && isa(varargin{1},'logical') + varargout{1} = geometry_wrapper(28, this, varargin{:}); + else + error('Arguments do not match any overload of function Test.return_bool'); + end + end + + function varargout = return_double(this, varargin) + if length(varargin) == 1 && isa(varargin{1},'double') + varargout{1} = geometry_wrapper(29, this, varargin{:}); + else + error('Arguments do not match any overload of function Test.return_double'); + end + end + + function varargout = return_field(this, varargin) + if length(varargin) == 1 && isa(varargin{1},'Test') + varargout{1} = geometry_wrapper(30, this, varargin{:}); + else + error('Arguments do not match any overload of function Test.return_field'); + end + end + + function varargout = return_int(this, varargin) + if length(varargin) == 1 && isa(varargin{1},'numeric') + varargout{1} = geometry_wrapper(31, this, varargin{:}); + else + error('Arguments do not match any overload of function Test.return_int'); + end + end + + function varargout = return_matrix1(this, varargin) + if length(varargin) == 1 && isa(varargin{1},'double') + varargout{1} = geometry_wrapper(32, this, varargin{:}); + else + error('Arguments do not match any overload of function Test.return_matrix1'); + end + end + + function varargout = return_matrix2(this, varargin) + if length(varargin) == 1 && isa(varargin{1},'double') + varargout{1} = geometry_wrapper(33, this, varargin{:}); + else + error('Arguments do not match any overload of function Test.return_matrix2'); + end + end + + function varargout = return_pair(this, varargin) + if length(varargin) == 2 && isa(varargin{1},'double') && isa(varargin{2},'double') + [ varargout{1} varargout{2} ] = geometry_wrapper(34, this, varargin{:}); + else + error('Arguments do not match any overload of function Test.return_pair'); + end + end + + function varargout = return_ptrs(this, varargin) + if length(varargin) == 2 && isa(varargin{1},'Test') && isa(varargin{2},'Test') + [ varargout{1} varargout{2} ] = geometry_wrapper(35, this, varargin{:}); + else + error('Arguments do not match any overload of function Test.return_ptrs'); + end + end + + function varargout = return_size_t(this, varargin) + if length(varargin) == 1 && isa(varargin{1},'numeric') + varargout{1} = geometry_wrapper(36, this, varargin{:}); + else + error('Arguments do not match any overload of function Test.return_size_t'); + end + end + + function varargout = return_string(this, varargin) + if length(varargin) == 1 && isa(varargin{1},'char') + varargout{1} = geometry_wrapper(37, this, varargin{:}); + else + error('Arguments do not match any overload of function Test.return_string'); + end + end + + function varargout = return_vector1(this, varargin) + if length(varargin) == 1 && isa(varargin{1},'double') + varargout{1} = geometry_wrapper(38, this, varargin{:}); + else + error('Arguments do not match any overload of function Test.return_vector1'); + end + end + + function varargout = return_vector2(this, varargin) + if length(varargin) == 1 && isa(varargin{1},'double') + varargout{1} = geometry_wrapper(39, this, varargin{:}); + else + error('Arguments do not match any overload of function Test.return_vector2'); + end + end + + end + + methods(Static = true) + end +end diff --git a/wrap/tests/expected/geometry_wrapper.cpp b/wrap/tests/expected/geometry_wrapper.cpp new file mode 100644 index 000000000..ade907701 --- /dev/null +++ b/wrap/tests/expected/geometry_wrapper.cpp @@ -0,0 +1,616 @@ +// automatically generated by wrap +#include +#include +#include + +#include +#include +#include + + +typedef std::set*> Collector_Point2; +static Collector_Point2 collector_Point2; +typedef std::set*> Collector_Point3; +static Collector_Point3 collector_Point3; +typedef std::set*> Collector_Test; +static Collector_Test collector_Test; + +void _deleteAllObjects() +{ + for(Collector_Point2::iterator iter = collector_Point2.begin(); + iter != collector_Point2.end(); ) { + delete *iter; + collector_Point2.erase(iter++); + } + for(Collector_Point3::iterator iter = collector_Point3.begin(); + iter != collector_Point3.end(); ) { + delete *iter; + collector_Point3.erase(iter++); + } + for(Collector_Test::iterator iter = collector_Test.begin(); + iter != collector_Test.end(); ) { + delete *iter; + collector_Test.erase(iter++); + } +} + +static bool _RTTIRegister_geometry_done = false; +void _geometry_RTTIRegister() { + std::map types; + + mxArray *registry = mexGetVariable("global", "gtsamwrap_rttiRegistry"); + if(!registry) + registry = mxCreateStructMatrix(1, 1, 0, NULL); + typedef std::pair StringPair; + BOOST_FOREACH(const StringPair& rtti_matlab, types) { + int fieldId = mxAddField(registry, rtti_matlab.first.c_str()); + if(fieldId < 0) + mexErrMsgTxt("gtsam wrap: Error indexing RTTI types, inheritance will not work correctly"); + mxArray *matlabName = mxCreateString(rtti_matlab.second.c_str()); + mxSetFieldByNumber(registry, 0, fieldId, matlabName); + } + if(mexPutVariable("global", "gtsamwrap_rttiRegistry", registry) != 0) + mexErrMsgTxt("gtsam wrap: Error indexing RTTI types, inheritance will not work correctly"); + mxDestroyArray(registry); +} + +void Point2_collectorInsertAndMakeBase_0(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + mexAtExit(&_deleteAllObjects); + typedef boost::shared_ptr Shared; + + Shared *self = *reinterpret_cast (mxGetData(in[0])); + collector_Point2.insert(self); +} + +void Point2_constructor_1(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + mexAtExit(&_deleteAllObjects); + typedef boost::shared_ptr Shared; + + Shared *self = new Shared(new Point2()); + collector_Point2.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[]) +{ + mexAtExit(&_deleteAllObjects); + 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); + 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[]) +{ + typedef boost::shared_ptr Shared; + checkArguments("delete_Point2",nargout,nargin,1); + Shared *self = *reinterpret_cast(mxGetData(in[0])); + Collector_Point2::iterator item; + item = collector_Point2.find(self); + if(item != collector_Point2.end()) { + delete self; + collector_Point2.erase(item); + } +} + +void Point2_argChar_4(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + typedef boost::shared_ptr Shared; + checkArguments("argChar",nargout,nargin-1,1); + Shared obj = unwrap_shared_ptr(in[0], "ptr_Point2"); + char a = unwrap< char >(in[1]); + obj->argChar(a); +} + +void Point2_argUChar_5(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + typedef boost::shared_ptr Shared; + checkArguments("argUChar",nargout,nargin-1,1); + Shared obj = unwrap_shared_ptr(in[0], "ptr_Point2"); + unsigned char a = unwrap< unsigned char >(in[1]); + obj->argUChar(a); +} + +void Point2_dim_6(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + typedef boost::shared_ptr Shared; + checkArguments("dim",nargout,nargin-1,0); + Shared obj = unwrap_shared_ptr(in[0], "ptr_Point2"); + out[0] = wrap< int >(obj->dim()); +} + +void Point2_returnChar_7(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + typedef boost::shared_ptr Shared; + checkArguments("returnChar",nargout,nargin-1,0); + Shared obj = unwrap_shared_ptr(in[0], "ptr_Point2"); + out[0] = wrap< char >(obj->returnChar()); +} + +void Point2_vectorConfusion_8(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + typedef boost::shared_ptr SharedVectorNotEigen; + typedef boost::shared_ptr Shared; + checkArguments("vectorConfusion",nargout,nargin-1,0); + Shared obj = unwrap_shared_ptr(in[0], "ptr_Point2"); + 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[]) +{ + typedef boost::shared_ptr Shared; + checkArguments("x",nargout,nargin-1,0); + Shared obj = unwrap_shared_ptr(in[0], "ptr_Point2"); + out[0] = wrap< double >(obj->x()); +} + +void Point2_y_10(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + typedef boost::shared_ptr Shared; + checkArguments("y",nargout,nargin-1,0); + Shared obj = unwrap_shared_ptr(in[0], "ptr_Point2"); + out[0] = wrap< double >(obj->y()); +} + +void Point3_collectorInsertAndMakeBase_11(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + mexAtExit(&_deleteAllObjects); +using namespace geometry; + typedef boost::shared_ptr Shared; + + Shared *self = *reinterpret_cast (mxGetData(in[0])); + collector_Point3.insert(self); +} + +void Point3_constructor_12(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + mexAtExit(&_deleteAllObjects); +using namespace geometry; + 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); + 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[]) +{ +using namespace geometry; + typedef boost::shared_ptr Shared; + checkArguments("delete_Point3",nargout,nargin,1); + Shared *self = *reinterpret_cast(mxGetData(in[0])); + Collector_Point3::iterator item; + item = collector_Point3.find(self); + if(item != collector_Point3.end()) { + delete self; + collector_Point3.erase(item); + } +} + +void Point3_norm_14(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ +using namespace geometry; + typedef boost::shared_ptr Shared; + checkArguments("norm",nargout,nargin-1,0); + Shared obj = unwrap_shared_ptr(in[0], "ptr_Point3"); + out[0] = wrap< double >(obj->norm()); +} + +void Point3_StaticFunctionRet_15(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ +using namespace geometry; + typedef boost::shared_ptr SharedPoint3; + typedef boost::shared_ptr Shared; + checkArguments("Point3.StaticFunctionRet",nargout,nargin,1); + double z = unwrap< double >(in[0]); + out[0] = wrap_shared_ptr(SharedPoint3(new Point3(Point3::StaticFunctionRet(z))),"Point3", false); +} + +void Point3_staticFunction_16(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ +using namespace geometry; + typedef boost::shared_ptr Shared; + checkArguments("Point3.staticFunction",nargout,nargin,0); + out[0] = wrap< double >(Point3::staticFunction()); +} + +void Test_collectorInsertAndMakeBase_17(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + mexAtExit(&_deleteAllObjects); +using namespace geometry; + typedef boost::shared_ptr Shared; + + Shared *self = *reinterpret_cast (mxGetData(in[0])); + collector_Test.insert(self); +} + +void Test_constructor_18(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + mexAtExit(&_deleteAllObjects); +using namespace geometry; + typedef boost::shared_ptr Shared; + + Shared *self = new Shared(new Test()); + collector_Test.insert(self); + out[0] = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL); + *reinterpret_cast (mxGetData(out[0])) = self; +} + +void Test_constructor_19(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + mexAtExit(&_deleteAllObjects); +using namespace geometry; + typedef boost::shared_ptr Shared; + + double a = unwrap< double >(in[0]); + Matrix b = unwrap< Matrix >(in[1]); + Shared *self = new Shared(new Test(a,b)); + collector_Test.insert(self); + out[0] = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL); + *reinterpret_cast (mxGetData(out[0])) = self; +} + +void Test_deconstructor_20(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ +using namespace geometry; + typedef boost::shared_ptr Shared; + checkArguments("delete_Test",nargout,nargin,1); + Shared *self = *reinterpret_cast(mxGetData(in[0])); + Collector_Test::iterator item; + item = collector_Test.find(self); + if(item != collector_Test.end()) { + delete self; + collector_Test.erase(item); + } +} + +void Test_arg_EigenConstRef_21(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ +using namespace geometry; + typedef boost::shared_ptr Shared; + checkArguments("arg_EigenConstRef",nargout,nargin-1,1); + Shared obj = unwrap_shared_ptr(in[0], "ptr_Test"); + Matrix& value = *unwrap_shared_ptr< Matrix >(in[1], "ptr_Matrix"); + obj->arg_EigenConstRef(value); +} + +void Test_create_MixedPtrs_22(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ +using namespace geometry; + typedef boost::shared_ptr SharedTest; + typedef boost::shared_ptr SharedTest; + typedef boost::shared_ptr Shared; + checkArguments("create_MixedPtrs",nargout,nargin-1,0); + Shared obj = unwrap_shared_ptr(in[0], "ptr_Test"); + out[0] = wrap_shared_ptr(SharedTest(new Test(obj->create_MixedPtrs().first)),"Test", false); + out[0] = wrap_shared_ptr(obj->create_MixedPtrs().second,"Test", false); +} + +void Test_create_ptrs_23(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ +using namespace geometry; + typedef boost::shared_ptr SharedTest; + typedef boost::shared_ptr SharedTest; + typedef boost::shared_ptr Shared; + checkArguments("create_ptrs",nargout,nargin-1,0); + Shared obj = unwrap_shared_ptr(in[0], "ptr_Test"); + out[0] = wrap_shared_ptr(obj->create_ptrs().first,"Test", false); + out[0] = wrap_shared_ptr(obj->create_ptrs().second,"Test", false); +} + +void Test_print_24(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ +using namespace geometry; + typedef boost::shared_ptr Shared; + checkArguments("print",nargout,nargin-1,0); + Shared obj = unwrap_shared_ptr(in[0], "ptr_Test"); + obj->print(); +} + +void Test_return_Point2Ptr_25(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ +using namespace geometry; + 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); +} + +void Test_return_Test_26(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ +using namespace geometry; + typedef boost::shared_ptr SharedTest; + typedef boost::shared_ptr Shared; + checkArguments("return_Test",nargout,nargin-1,1); + Shared obj = unwrap_shared_ptr(in[0], "ptr_Test"); + boost::shared_ptr value = unwrap_shared_ptr< Test >(in[1], "ptr_Test"); + out[0] = wrap_shared_ptr(SharedTest(new Test(obj->return_Test(value))),"Test", false); +} + +void Test_return_TestPtr_27(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ +using namespace geometry; + typedef boost::shared_ptr SharedTest; + typedef boost::shared_ptr Shared; + checkArguments("return_TestPtr",nargout,nargin-1,1); + Shared obj = unwrap_shared_ptr(in[0], "ptr_Test"); + boost::shared_ptr value = unwrap_shared_ptr< Test >(in[1], "ptr_Test"); + out[0] = wrap_shared_ptr(obj->return_TestPtr(value),"Test", false); +} + +void Test_return_bool_28(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ +using namespace geometry; + typedef boost::shared_ptr Shared; + checkArguments("return_bool",nargout,nargin-1,1); + Shared obj = unwrap_shared_ptr(in[0], "ptr_Test"); + bool value = unwrap< bool >(in[1]); + out[0] = wrap< bool >(obj->return_bool(value)); +} + +void Test_return_double_29(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ +using namespace geometry; + typedef boost::shared_ptr Shared; + checkArguments("return_double",nargout,nargin-1,1); + Shared obj = unwrap_shared_ptr(in[0], "ptr_Test"); + double value = unwrap< double >(in[1]); + out[0] = wrap< double >(obj->return_double(value)); +} + +void Test_return_field_30(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ +using namespace geometry; + typedef boost::shared_ptr Shared; + checkArguments("return_field",nargout,nargin-1,1); + Shared obj = unwrap_shared_ptr(in[0], "ptr_Test"); + Test& t = *unwrap_shared_ptr< Test >(in[1], "ptr_Test"); + out[0] = wrap< bool >(obj->return_field(t)); +} + +void Test_return_int_31(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ +using namespace geometry; + typedef boost::shared_ptr Shared; + checkArguments("return_int",nargout,nargin-1,1); + Shared obj = unwrap_shared_ptr(in[0], "ptr_Test"); + int value = unwrap< int >(in[1]); + out[0] = wrap< int >(obj->return_int(value)); +} + +void Test_return_matrix1_32(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ +using namespace geometry; + typedef boost::shared_ptr Shared; + checkArguments("return_matrix1",nargout,nargin-1,1); + Shared obj = unwrap_shared_ptr(in[0], "ptr_Test"); + Matrix value = unwrap< Matrix >(in[1]); + out[0] = wrap< Matrix >(obj->return_matrix1(value)); +} + +void Test_return_matrix2_33(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ +using namespace geometry; + typedef boost::shared_ptr Shared; + checkArguments("return_matrix2",nargout,nargin-1,1); + Shared obj = unwrap_shared_ptr(in[0], "ptr_Test"); + Matrix value = unwrap< Matrix >(in[1]); + out[0] = wrap< Matrix >(obj->return_matrix2(value)); +} + +void Test_return_pair_34(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ +using namespace geometry; + typedef boost::shared_ptr Shared; + checkArguments("return_pair",nargout,nargin-1,2); + Shared obj = unwrap_shared_ptr(in[0], "ptr_Test"); + Vector v = unwrap< Vector >(in[1]); + Matrix A = unwrap< Matrix >(in[2]); + out[0] = wrap< Vector >(obj->return_pair(v,A).first); + out[1] = wrap< Matrix >(obj->return_pair(v,A).second); +} + +void Test_return_ptrs_35(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ +using namespace geometry; + typedef boost::shared_ptr SharedTest; + typedef boost::shared_ptr SharedTest; + typedef boost::shared_ptr Shared; + checkArguments("return_ptrs",nargout,nargin-1,2); + Shared obj = unwrap_shared_ptr(in[0], "ptr_Test"); + boost::shared_ptr p1 = unwrap_shared_ptr< Test >(in[1], "ptr_Test"); + boost::shared_ptr p2 = unwrap_shared_ptr< Test >(in[2], "ptr_Test"); + out[0] = wrap_shared_ptr(obj->return_ptrs(p1,p2).first,"Test", false); + out[0] = wrap_shared_ptr(obj->return_ptrs(p1,p2).second,"Test", false); +} + +void Test_return_size_t_36(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ +using namespace geometry; + typedef boost::shared_ptr Shared; + checkArguments("return_size_t",nargout,nargin-1,1); + Shared obj = unwrap_shared_ptr(in[0], "ptr_Test"); + size_t value = unwrap< size_t >(in[1]); + out[0] = wrap< size_t >(obj->return_size_t(value)); +} + +void Test_return_string_37(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ +using namespace geometry; + typedef boost::shared_ptr Shared; + checkArguments("return_string",nargout,nargin-1,1); + Shared obj = unwrap_shared_ptr(in[0], "ptr_Test"); + string value = unwrap< string >(in[1]); + out[0] = wrap< string >(obj->return_string(value)); +} + +void Test_return_vector1_38(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ +using namespace geometry; + typedef boost::shared_ptr Shared; + checkArguments("return_vector1",nargout,nargin-1,1); + Shared obj = unwrap_shared_ptr(in[0], "ptr_Test"); + Vector value = unwrap< Vector >(in[1]); + out[0] = wrap< Vector >(obj->return_vector1(value)); +} + +void Test_return_vector2_39(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ +using namespace geometry; + typedef boost::shared_ptr Shared; + checkArguments("return_vector2",nargout,nargin-1,1); + Shared obj = unwrap_shared_ptr(in[0], "ptr_Test"); + Vector value = unwrap< Vector >(in[1]); + out[0] = wrap< Vector >(obj->return_vector2(value)); +} + + +void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + mstream mout; + std::streambuf *outbuf = std::cout.rdbuf(&mout); + + if(!_RTTIRegister_geometry_done) { + _geometry_RTTIRegister(); + _RTTIRegister_geometry_done = true; + } + int id = unwrap(in[0]); + + switch(id) { + case 0: + Point2_collectorInsertAndMakeBase_0(nargout, out, nargin-1, in+1); + break; + case 1: + Point2_constructor_1(nargout, out, nargin-1, in+1); + break; + case 2: + Point2_constructor_2(nargout, out, nargin-1, in+1); + break; + case 3: + Point2_deconstructor_3(nargout, out, nargin-1, in+1); + break; + case 4: + Point2_argChar_4(nargout, out, nargin-1, in+1); + break; + case 5: + Point2_argUChar_5(nargout, out, nargin-1, in+1); + break; + case 6: + Point2_dim_6(nargout, out, nargin-1, in+1); + break; + case 7: + Point2_returnChar_7(nargout, out, nargin-1, in+1); + break; + case 8: + Point2_vectorConfusion_8(nargout, out, nargin-1, in+1); + break; + case 9: + Point2_x_9(nargout, out, nargin-1, in+1); + break; + case 10: + Point2_y_10(nargout, out, nargin-1, in+1); + break; + case 11: + Point3_collectorInsertAndMakeBase_11(nargout, out, nargin-1, in+1); + break; + case 12: + Point3_constructor_12(nargout, out, nargin-1, in+1); + break; + case 13: + Point3_deconstructor_13(nargout, out, nargin-1, in+1); + break; + case 14: + Point3_norm_14(nargout, out, nargin-1, in+1); + break; + case 15: + Point3_StaticFunctionRet_15(nargout, out, nargin-1, in+1); + break; + case 16: + Point3_staticFunction_16(nargout, out, nargin-1, in+1); + break; + case 17: + Test_collectorInsertAndMakeBase_17(nargout, out, nargin-1, in+1); + break; + case 18: + Test_constructor_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); + break; + case 21: + Test_arg_EigenConstRef_21(nargout, out, nargin-1, in+1); + break; + case 22: + Test_create_MixedPtrs_22(nargout, out, nargin-1, in+1); + break; + case 23: + Test_create_ptrs_23(nargout, out, nargin-1, in+1); + break; + case 24: + Test_print_24(nargout, out, nargin-1, in+1); + break; + case 25: + Test_return_Point2Ptr_25(nargout, out, nargin-1, in+1); + break; + case 26: + Test_return_Test_26(nargout, out, nargin-1, in+1); + break; + case 27: + Test_return_TestPtr_27(nargout, out, nargin-1, in+1); + break; + case 28: + Test_return_bool_28(nargout, out, nargin-1, in+1); + break; + case 29: + Test_return_double_29(nargout, out, nargin-1, in+1); + break; + case 30: + Test_return_field_30(nargout, out, nargin-1, in+1); + break; + case 31: + Test_return_int_31(nargout, out, nargin-1, in+1); + break; + case 32: + Test_return_matrix1_32(nargout, out, nargin-1, in+1); + break; + case 33: + Test_return_matrix2_33(nargout, out, nargin-1, in+1); + break; + case 34: + Test_return_pair_34(nargout, out, nargin-1, in+1); + break; + case 35: + Test_return_ptrs_35(nargout, out, nargin-1, in+1); + break; + case 36: + Test_return_size_t_36(nargout, out, nargin-1, in+1); + break; + case 37: + Test_return_string_37(nargout, out, nargin-1, in+1); + break; + case 38: + Test_return_vector1_38(nargout, out, nargin-1, in+1); + break; + case 39: + Test_return_vector2_39(nargout, out, nargin-1, in+1); + break; + } + + std::cout.rdbuf(outbuf); +} diff --git a/wrap/tests/expected/make_geometry.m b/wrap/tests/expected/make_geometry.m deleted file mode 100644 index d77459ed8..000000000 --- a/wrap/tests/expected/make_geometry.m +++ /dev/null @@ -1,59 +0,0 @@ -% automatically generated by wrap -echo on - -toolboxpath = mfilename('fullpath'); -delims = find(toolboxpath == '/' | toolboxpath == '\'); -toolboxpath = toolboxpath(1:(delims(end)-1)); -clear delims -addpath(toolboxpath); - -%% Point2 -cd(toolboxpath) -mex -O5 new_Point2.cpp - -cd @Point2 -mex -O5 x.cpp -mex -O5 y.cpp -mex -O5 dim.cpp -mex -O5 returnChar.cpp -mex -O5 argChar.cpp -mex -O5 argUChar.cpp -mex -O5 vectorConfusion.cpp - -%% Point3 -cd(toolboxpath) -mex -O5 new_Point3.cpp -mex -O5 Point3_staticFunction.cpp -mex -O5 Point3_StaticFunctionRet.cpp - -cd @Point3 -mex -O5 norm.cpp - -%% Test -cd(toolboxpath) -mex -O5 new_Test.cpp - -cd @Test -mex -O5 return_pair.cpp -mex -O5 return_bool.cpp -mex -O5 return_size_t.cpp -mex -O5 return_int.cpp -mex -O5 return_double.cpp -mex -O5 return_string.cpp -mex -O5 return_vector1.cpp -mex -O5 return_matrix1.cpp -mex -O5 return_vector2.cpp -mex -O5 return_matrix2.cpp -mex -O5 arg_EigenConstRef.cpp -mex -O5 return_field.cpp -mex -O5 return_TestPtr.cpp -mex -O5 return_Test.cpp -mex -O5 return_Point2Ptr.cpp -mex -O5 create_ptrs.cpp -mex -O5 create_MixedPtrs.cpp -mex -O5 return_ptrs.cpp -mex -O5 print.cpp - -cd(toolboxpath) - -echo off diff --git a/wrap/tests/expected/new_Point2.cpp b/wrap/tests/expected/new_Point2.cpp deleted file mode 100644 index b24642ad4..000000000 --- a/wrap/tests/expected/new_Point2.cpp +++ /dev/null @@ -1,41 +0,0 @@ -// automatically generated by wrap -#include -#include -typedef boost::shared_ptr Shared; - -static std::set collector; - -void cleanup(void) { - for(std::set::iterator iter = collector.begin(); iter != collector.end(); ) { - delete *iter; - collector.erase(iter++); - } -} -void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - mexAtExit(cleanup); - - const mxArray* input = in[0]; - Shared* self = *(Shared**) mxGetData(input); - - if(self) { - if(nargin > 1) { - collector.insert(self); - } - else if(collector.erase(self)) - delete self; - } else { - int nc = unwrap(in[1]); - - if(nc == 0) - self = new Shared(new Point2()); - if(nc == 1) { - double x = unwrap< double >(in[2]); - double y = unwrap< double >(in[3]); - self = new Shared(new Point2(x,y)); - } - collector.insert(self); - out[0] = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL); - *reinterpret_cast (mxGetPr(out[0])) = self; - } -} diff --git a/wrap/tests/expected/new_Point2.m b/wrap/tests/expected/new_Point2.m deleted file mode 100644 index 9a6edd425..000000000 --- a/wrap/tests/expected/new_Point2.m +++ /dev/null @@ -1,4 +0,0 @@ -% automatically generated by wrap -function result = new_Point2(obj,x,y) - error('need to compile new_Point2.cpp'); -end diff --git a/wrap/tests/expected/new_Point3.cpp b/wrap/tests/expected/new_Point3.cpp deleted file mode 100644 index 2e715263b..000000000 --- a/wrap/tests/expected/new_Point3.cpp +++ /dev/null @@ -1,41 +0,0 @@ -// automatically generated by wrap -#include -#include -using namespace geometry; -typedef boost::shared_ptr Shared; - -static std::set collector; - -void cleanup(void) { - for(std::set::iterator iter = collector.begin(); iter != collector.end(); ) { - delete *iter; - collector.erase(iter++); - } -} -void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - mexAtExit(cleanup); - - const mxArray* input = in[0]; - Shared* self = *(Shared**) mxGetData(input); - - if(self) { - if(nargin > 1) { - collector.insert(self); - } - else if(collector.erase(self)) - delete self; - } else { - int nc = unwrap(in[1]); - - if(nc == 0) { - double x = unwrap< double >(in[2]); - double y = unwrap< double >(in[3]); - double z = unwrap< double >(in[4]); - self = new Shared(new Point3(x,y,z)); - } - collector.insert(self); - out[0] = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL); - *reinterpret_cast (mxGetPr(out[0])) = self; - } -} diff --git a/wrap/tests/expected/new_Point3.m b/wrap/tests/expected/new_Point3.m deleted file mode 100644 index 9cca5daa5..000000000 --- a/wrap/tests/expected/new_Point3.m +++ /dev/null @@ -1,4 +0,0 @@ -% automatically generated by wrap -function result = new_Point3(obj,x,y,z) - error('need to compile new_Point3.cpp'); -end diff --git a/wrap/tests/expected/new_Test.cpp b/wrap/tests/expected/new_Test.cpp deleted file mode 100644 index 57ac1a4ea..000000000 --- a/wrap/tests/expected/new_Test.cpp +++ /dev/null @@ -1,42 +0,0 @@ -// automatically generated by wrap -#include -#include -using namespace geometry; -typedef boost::shared_ptr Shared; - -static std::set collector; - -void cleanup(void) { - for(std::set::iterator iter = collector.begin(); iter != collector.end(); ) { - delete *iter; - collector.erase(iter++); - } -} -void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - mexAtExit(cleanup); - - const mxArray* input = in[0]; - Shared* self = *(Shared**) mxGetData(input); - - if(self) { - if(nargin > 1) { - collector.insert(self); - } - else if(collector.erase(self)) - delete self; - } else { - int nc = unwrap(in[1]); - - if(nc == 0) - self = new Shared(new Test()); - if(nc == 1) { - double a = unwrap< double >(in[2]); - Matrix b = unwrap< Matrix >(in[3]); - self = new Shared(new Test(a,b)); - } - collector.insert(self); - out[0] = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL); - *reinterpret_cast (mxGetPr(out[0])) = self; - } -} diff --git a/wrap/tests/expected/new_Test.m b/wrap/tests/expected/new_Test.m deleted file mode 100644 index ec9a13f63..000000000 --- a/wrap/tests/expected/new_Test.m +++ /dev/null @@ -1,4 +0,0 @@ -% automatically generated by wrap -function result = new_Test(obj,a,b) - error('need to compile new_Test.cpp'); -end diff --git a/wrap/tests/expected_namespaces/@ClassD/ClassD.m b/wrap/tests/expected_namespaces/@ClassD/ClassD.m deleted file mode 100644 index 90fbf48a4..000000000 --- a/wrap/tests/expected_namespaces/@ClassD/ClassD.m +++ /dev/null @@ -1,21 +0,0 @@ -% automatically generated by wrap -classdef ClassD < handle - properties - self = 0 - end - methods - function obj = ClassD(varargin) - if (nargin == 0), obj.self = new_ClassD(0,0); end - if nargin ==14, new_ClassD(varargin{1},0); end - if nargin ~= 13 && nargin ~= 14 && obj.self == 0, error('ClassD constructor failed'); end - end - function delete(obj) - if obj.self ~= 0 - new_ClassD(obj.self); - obj.self = 0; - end - end - function display(obj), obj.print(''); end - function disp(obj), obj.display; end - end -end diff --git a/wrap/tests/expected_namespaces/@ns1ClassA/ns1ClassA.m b/wrap/tests/expected_namespaces/@ns1ClassA/ns1ClassA.m deleted file mode 100644 index 727e020ae..000000000 --- a/wrap/tests/expected_namespaces/@ns1ClassA/ns1ClassA.m +++ /dev/null @@ -1,21 +0,0 @@ -% automatically generated by wrap -classdef ns1ClassA < handle - properties - self = 0 - end - methods - function obj = ns1ClassA(varargin) - if (nargin == 0), obj.self = new_ns1ClassA(0,0); end - if nargin ==14, new_ns1ClassA(varargin{1},0); end - if nargin ~= 13 && nargin ~= 14 && obj.self == 0, error('ns1ClassA constructor failed'); end - end - function delete(obj) - if obj.self ~= 0 - new_ns1ClassA(obj.self); - obj.self = 0; - end - end - function display(obj), obj.print(''); end - function disp(obj), obj.display; end - end -end diff --git a/wrap/tests/expected_namespaces/@ns1ClassB/ns1ClassB.m b/wrap/tests/expected_namespaces/@ns1ClassB/ns1ClassB.m deleted file mode 100644 index 19b0a73b9..000000000 --- a/wrap/tests/expected_namespaces/@ns1ClassB/ns1ClassB.m +++ /dev/null @@ -1,21 +0,0 @@ -% automatically generated by wrap -classdef ns1ClassB < handle - properties - self = 0 - end - methods - function obj = ns1ClassB(varargin) - if (nargin == 0), obj.self = new_ns1ClassB(0,0); end - if nargin ==14, new_ns1ClassB(varargin{1},0); end - if nargin ~= 13 && nargin ~= 14 && obj.self == 0, error('ns1ClassB constructor failed'); end - end - function delete(obj) - if obj.self ~= 0 - new_ns1ClassB(obj.self); - obj.self = 0; - end - end - function display(obj), obj.print(''); end - function disp(obj), obj.display; end - end -end diff --git a/wrap/tests/expected_namespaces/@ns2ClassA/memberFunction.cpp b/wrap/tests/expected_namespaces/@ns2ClassA/memberFunction.cpp deleted file mode 100644 index 70d0a7968..000000000 --- a/wrap/tests/expected_namespaces/@ns2ClassA/memberFunction.cpp +++ /dev/null @@ -1,12 +0,0 @@ -// automatically generated by wrap -#include -#include -#include -typedef boost::shared_ptr Shared; -void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("memberFunction",nargout,nargin-1,0); - Shared obj = unwrap_shared_ptr(in[0], "ns2::ClassA"); - double result = obj->memberFunction(); - out[0] = wrap< double >(result); -} diff --git a/wrap/tests/expected_namespaces/@ns2ClassA/memberFunction.m b/wrap/tests/expected_namespaces/@ns2ClassA/memberFunction.m deleted file mode 100644 index 41587c2bc..000000000 --- a/wrap/tests/expected_namespaces/@ns2ClassA/memberFunction.m +++ /dev/null @@ -1,4 +0,0 @@ -% result = obj.memberFunction() -function result = memberFunction(obj) - error('need to compile memberFunction.cpp'); -end diff --git a/wrap/tests/expected_namespaces/@ns2ClassA/ns2ClassA.m b/wrap/tests/expected_namespaces/@ns2ClassA/ns2ClassA.m deleted file mode 100644 index 27de74dc3..000000000 --- a/wrap/tests/expected_namespaces/@ns2ClassA/ns2ClassA.m +++ /dev/null @@ -1,21 +0,0 @@ -% automatically generated by wrap -classdef ns2ClassA < handle - properties - self = 0 - end - methods - function obj = ns2ClassA(varargin) - if (nargin == 0), obj.self = new_ns2ClassA(0,0); end - if nargin ==14, new_ns2ClassA(varargin{1},0); end - if nargin ~= 13 && nargin ~= 14 && obj.self == 0, error('ns2ClassA constructor failed'); end - end - function delete(obj) - if obj.self ~= 0 - new_ns2ClassA(obj.self); - obj.self = 0; - end - end - function display(obj), obj.print(''); end - function disp(obj), obj.display; end - end -end diff --git a/wrap/tests/expected_namespaces/@ns2ClassA/nsArg.cpp b/wrap/tests/expected_namespaces/@ns2ClassA/nsArg.cpp deleted file mode 100644 index 498d90649..000000000 --- a/wrap/tests/expected_namespaces/@ns2ClassA/nsArg.cpp +++ /dev/null @@ -1,13 +0,0 @@ -// automatically generated by wrap -#include -#include -#include -typedef boost::shared_ptr Shared; -void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("nsArg",nargout,nargin-1,1); - Shared obj = unwrap_shared_ptr(in[0], "ns2::ClassA"); - ns1::ClassB& arg = *unwrap_shared_ptr< ns1::ClassB >(in[1], "ns1ClassB"); - int result = obj->nsArg(arg); - out[0] = wrap< int >(result); -} diff --git a/wrap/tests/expected_namespaces/@ns2ClassA/nsArg.m b/wrap/tests/expected_namespaces/@ns2ClassA/nsArg.m deleted file mode 100644 index 1e3f5865d..000000000 --- a/wrap/tests/expected_namespaces/@ns2ClassA/nsArg.m +++ /dev/null @@ -1,4 +0,0 @@ -% result = obj.nsArg(arg) -function result = nsArg(obj,arg) - error('need to compile nsArg.cpp'); -end diff --git a/wrap/tests/expected_namespaces/@ns2ClassA/nsReturn.cpp b/wrap/tests/expected_namespaces/@ns2ClassA/nsReturn.cpp deleted file mode 100644 index 996bf8913..000000000 --- a/wrap/tests/expected_namespaces/@ns2ClassA/nsReturn.cpp +++ /dev/null @@ -1,15 +0,0 @@ -// automatically generated by wrap -#include -#include -#include -typedef boost::shared_ptr SharedClassB; -typedef boost::shared_ptr Shared; -void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("nsReturn",nargout,nargin-1,1); - Shared obj = unwrap_shared_ptr(in[0], "ns2::ClassA"); - double q = unwrap< double >(in[1]); - ns2::ns3::ClassB result = obj->nsReturn(q); - SharedClassB* ret = new SharedClassB(new ns2::ns3::ClassB(result)); - out[0] = wrap_collect_shared_ptr(ret,"ns2ns3ClassB"); -} diff --git a/wrap/tests/expected_namespaces/@ns2ClassA/nsReturn.m b/wrap/tests/expected_namespaces/@ns2ClassA/nsReturn.m deleted file mode 100644 index f1f74b614..000000000 --- a/wrap/tests/expected_namespaces/@ns2ClassA/nsReturn.m +++ /dev/null @@ -1,4 +0,0 @@ -% result = obj.nsReturn(q) -function result = nsReturn(obj,q) - error('need to compile nsReturn.cpp'); -end diff --git a/wrap/tests/expected_namespaces/@ns2ClassC/ns2ClassC.m b/wrap/tests/expected_namespaces/@ns2ClassC/ns2ClassC.m deleted file mode 100644 index 2425b59bd..000000000 --- a/wrap/tests/expected_namespaces/@ns2ClassC/ns2ClassC.m +++ /dev/null @@ -1,21 +0,0 @@ -% automatically generated by wrap -classdef ns2ClassC < handle - properties - self = 0 - end - methods - function obj = ns2ClassC(varargin) - if (nargin == 0), obj.self = new_ns2ClassC(0,0); end - if nargin ==14, new_ns2ClassC(varargin{1},0); end - if nargin ~= 13 && nargin ~= 14 && obj.self == 0, error('ns2ClassC constructor failed'); end - end - function delete(obj) - if obj.self ~= 0 - new_ns2ClassC(obj.self); - obj.self = 0; - end - end - function display(obj), obj.print(''); end - function disp(obj), obj.display; end - end -end diff --git a/wrap/tests/expected_namespaces/@ns2ns3ClassB/ns2ns3ClassB.m b/wrap/tests/expected_namespaces/@ns2ns3ClassB/ns2ns3ClassB.m deleted file mode 100644 index de7f7a3ca..000000000 --- a/wrap/tests/expected_namespaces/@ns2ns3ClassB/ns2ns3ClassB.m +++ /dev/null @@ -1,21 +0,0 @@ -% automatically generated by wrap -classdef ns2ns3ClassB < handle - properties - self = 0 - end - methods - function obj = ns2ns3ClassB(varargin) - if (nargin == 0), obj.self = new_ns2ns3ClassB(0,0); end - if nargin ==14, new_ns2ns3ClassB(varargin{1},0); end - if nargin ~= 13 && nargin ~= 14 && obj.self == 0, error('ns2ns3ClassB constructor failed'); end - end - function delete(obj) - if obj.self ~= 0 - new_ns2ns3ClassB(obj.self); - obj.self = 0; - end - end - function display(obj), obj.print(''); end - function disp(obj), obj.display; end - end -end diff --git a/wrap/tests/expected_namespaces/ClassD.m b/wrap/tests/expected_namespaces/ClassD.m new file mode 100644 index 000000000..3fb8d4837 --- /dev/null +++ b/wrap/tests/expected_namespaces/ClassD.m @@ -0,0 +1,31 @@ +% automatically generated by wrap +classdef ClassD < handle + properties + ptr_ClassD = 0 + end + methods + function obj = ClassD(varargin) + if nargin == 2 && isa(varargin{1}, 'uint64') && varargin{1} == uint64(5139824614673773682) + my_ptr = varargin{2}; + testNamespaces_wrapper(19, my_ptr); + elseif nargin == 0 + my_ptr = testNamespaces_wrapper(20); + else + error('Arguments do not match any overload of ClassD constructor'); + end + obj.ptr_ClassD = my_ptr; + end + + function delete(obj) + testNamespaces_wrapper(21, obj.ptr_ClassD); + end + + function display(obj), obj.print(''); end + + function disp(obj), obj.display; end + + end + + methods(Static = true) + end +end diff --git a/wrap/tests/expected_namespaces/Makefile b/wrap/tests/expected_namespaces/Makefile deleted file mode 100644 index 1cb09b8b9..000000000 --- a/wrap/tests/expected_namespaces/Makefile +++ /dev/null @@ -1,65 +0,0 @@ -# automatically generated by wrap - -MEX = mex -MEXENDING = mexa64 -PATH_TO_WRAP = /not_really_a_real_path/borg/gtsam/wrap -mex_flags = -O5 - -all: ns1ClassA ns1ClassB ns2ClassA ns2ns3ClassB ns2ClassC ClassD - -# ns1ClassA -new_ns1ClassA.$(MEXENDING): new_ns1ClassA.cpp $(PATH_TO_WRAP)/matlab.h - $(MEX) $(mex_flags) new_ns1ClassA.cpp -output new_ns1ClassA - -ns1ClassA: new_ns1ClassA.$(MEXENDING) - -# ns1ClassB -new_ns1ClassB.$(MEXENDING): new_ns1ClassB.cpp $(PATH_TO_WRAP)/matlab.h - $(MEX) $(mex_flags) new_ns1ClassB.cpp -output new_ns1ClassB - -ns1ClassB: new_ns1ClassB.$(MEXENDING) - -# ns2ClassA -new_ns2ClassA.$(MEXENDING): new_ns2ClassA.cpp $(PATH_TO_WRAP)/matlab.h - $(MEX) $(mex_flags) new_ns2ClassA.cpp -output new_ns2ClassA -ns2ClassA_afunction.$(MEXENDING): ns2ClassA_afunction.cpp $(PATH_TO_WRAP)/matlab.h - $(MEX) $(mex_flags) ns2ClassA_afunction.cpp -output ns2ClassA_afunction -@ns2ClassA/memberFunction.$(MEXENDING): @ns2ClassA/memberFunction.cpp $(PATH_TO_WRAP)/matlab.h - $(MEX) $(mex_flags) @ns2ClassA/memberFunction.cpp -output @ns2ClassA/memberFunction -@ns2ClassA/nsArg.$(MEXENDING): @ns2ClassA/nsArg.cpp $(PATH_TO_WRAP)/matlab.h - $(MEX) $(mex_flags) @ns2ClassA/nsArg.cpp -output @ns2ClassA/nsArg -@ns2ClassA/nsReturn.$(MEXENDING): @ns2ClassA/nsReturn.cpp $(PATH_TO_WRAP)/matlab.h - $(MEX) $(mex_flags) @ns2ClassA/nsReturn.cpp -output @ns2ClassA/nsReturn - -ns2ClassA: new_ns2ClassA.$(MEXENDING) ns2ClassA_afunction.$(MEXENDING) @ns2ClassA/memberFunction.$(MEXENDING) @ns2ClassA/nsArg.$(MEXENDING) @ns2ClassA/nsReturn.$(MEXENDING) - -# ns2ns3ClassB -new_ns2ns3ClassB.$(MEXENDING): new_ns2ns3ClassB.cpp $(PATH_TO_WRAP)/matlab.h - $(MEX) $(mex_flags) new_ns2ns3ClassB.cpp -output new_ns2ns3ClassB - -ns2ns3ClassB: new_ns2ns3ClassB.$(MEXENDING) - -# ns2ClassC -new_ns2ClassC.$(MEXENDING): new_ns2ClassC.cpp $(PATH_TO_WRAP)/matlab.h - $(MEX) $(mex_flags) new_ns2ClassC.cpp -output new_ns2ClassC - -ns2ClassC: new_ns2ClassC.$(MEXENDING) - -# ClassD -new_ClassD.$(MEXENDING): new_ClassD.cpp $(PATH_TO_WRAP)/matlab.h - $(MEX) $(mex_flags) new_ClassD.cpp -output new_ClassD - -ClassD: new_ClassD.$(MEXENDING) - - - -clean: - rm -rf *.$(MEXENDING) - rm -rf @ns1ClassA/*.$(MEXENDING) - rm -rf @ns1ClassB/*.$(MEXENDING) - rm -rf @ns2ClassA/*.$(MEXENDING) - rm -rf @ns2ns3ClassB/*.$(MEXENDING) - rm -rf @ns2ClassC/*.$(MEXENDING) - rm -rf @ClassD/*.$(MEXENDING) - - diff --git a/wrap/tests/expected_namespaces/make_testNamespaces.m b/wrap/tests/expected_namespaces/make_testNamespaces.m deleted file mode 100644 index 5cf086db8..000000000 --- a/wrap/tests/expected_namespaces/make_testNamespaces.m +++ /dev/null @@ -1,52 +0,0 @@ -% automatically generated by wrap -echo on - -toolboxpath = mfilename('fullpath'); -delims = find(toolboxpath == '/' | toolboxpath == '\'); -toolboxpath = toolboxpath(1:(delims(end)-1)); -clear delims -addpath(toolboxpath); - -%% ns1ClassA -cd(toolboxpath) -mex -O5 new_ns1ClassA.cpp - -cd @ns1ClassA - -%% ns1ClassB -cd(toolboxpath) -mex -O5 new_ns1ClassB.cpp - -cd @ns1ClassB - -%% ns2ClassA -cd(toolboxpath) -mex -O5 new_ns2ClassA.cpp -mex -O5 ns2ClassA_afunction.cpp - -cd @ns2ClassA -mex -O5 memberFunction.cpp -mex -O5 nsArg.cpp -mex -O5 nsReturn.cpp - -%% ns2ns3ClassB -cd(toolboxpath) -mex -O5 new_ns2ns3ClassB.cpp - -cd @ns2ns3ClassB - -%% ns2ClassC -cd(toolboxpath) -mex -O5 new_ns2ClassC.cpp - -cd @ns2ClassC - -%% ClassD -cd(toolboxpath) -mex -O5 new_ClassD.cpp - -cd @ClassD - -cd(toolboxpath) - -echo off diff --git a/wrap/tests/expected_namespaces/new_ClassD.cpp b/wrap/tests/expected_namespaces/new_ClassD.cpp deleted file mode 100644 index d7a7e4908..000000000 --- a/wrap/tests/expected_namespaces/new_ClassD.cpp +++ /dev/null @@ -1,36 +0,0 @@ -// automatically generated by wrap -#include -#include -typedef boost::shared_ptr Shared; - -static std::set collector; - -void cleanup(void) { - for(std::set::iterator iter = collector.begin(); iter != collector.end(); ) { - delete *iter; - collector.erase(iter++); - } -} -void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - mexAtExit(cleanup); - - const mxArray* input = in[0]; - Shared* self = *(Shared**) mxGetData(input); - - if(self) { - if(nargin > 1) { - collector.insert(self); - } - else if(collector.erase(self)) - delete self; - } else { - int nc = unwrap(in[1]); - - if(nc == 0) - self = new Shared(new ClassD()); - collector.insert(self); - out[0] = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL); - *reinterpret_cast (mxGetPr(out[0])) = self; - } -} diff --git a/wrap/tests/expected_namespaces/new_ClassD.m b/wrap/tests/expected_namespaces/new_ClassD.m deleted file mode 100644 index d12bfffb1..000000000 --- a/wrap/tests/expected_namespaces/new_ClassD.m +++ /dev/null @@ -1,4 +0,0 @@ -% automatically generated by wrap -function result = new_ClassD(obj) - error('need to compile new_ClassD.cpp'); -end diff --git a/wrap/tests/expected_namespaces/new_ns1ClassA.cpp b/wrap/tests/expected_namespaces/new_ns1ClassA.cpp deleted file mode 100644 index 2554eafc1..000000000 --- a/wrap/tests/expected_namespaces/new_ns1ClassA.cpp +++ /dev/null @@ -1,36 +0,0 @@ -// automatically generated by wrap -#include -#include -typedef boost::shared_ptr Shared; - -static std::set collector; - -void cleanup(void) { - for(std::set::iterator iter = collector.begin(); iter != collector.end(); ) { - delete *iter; - collector.erase(iter++); - } -} -void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - mexAtExit(cleanup); - - const mxArray* input = in[0]; - Shared* self = *(Shared**) mxGetData(input); - - if(self) { - if(nargin > 1) { - collector.insert(self); - } - else if(collector.erase(self)) - delete self; - } else { - int nc = unwrap(in[1]); - - if(nc == 0) - self = new Shared(new ns1::ClassA()); - collector.insert(self); - out[0] = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL); - *reinterpret_cast (mxGetPr(out[0])) = self; - } -} diff --git a/wrap/tests/expected_namespaces/new_ns1ClassA.m b/wrap/tests/expected_namespaces/new_ns1ClassA.m deleted file mode 100644 index 4412baae1..000000000 --- a/wrap/tests/expected_namespaces/new_ns1ClassA.m +++ /dev/null @@ -1,4 +0,0 @@ -% automatically generated by wrap -function result = new_ns1ClassA(obj) - error('need to compile new_ns1ClassA.cpp'); -end diff --git a/wrap/tests/expected_namespaces/new_ns1ClassB.cpp b/wrap/tests/expected_namespaces/new_ns1ClassB.cpp deleted file mode 100644 index bc1dd313c..000000000 --- a/wrap/tests/expected_namespaces/new_ns1ClassB.cpp +++ /dev/null @@ -1,37 +0,0 @@ -// automatically generated by wrap -#include -#include -#include -typedef boost::shared_ptr Shared; - -static std::set collector; - -void cleanup(void) { - for(std::set::iterator iter = collector.begin(); iter != collector.end(); ) { - delete *iter; - collector.erase(iter++); - } -} -void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - mexAtExit(cleanup); - - const mxArray* input = in[0]; - Shared* self = *(Shared**) mxGetData(input); - - if(self) { - if(nargin > 1) { - collector.insert(self); - } - else if(collector.erase(self)) - delete self; - } else { - int nc = unwrap(in[1]); - - if(nc == 0) - self = new Shared(new ns1::ClassB()); - collector.insert(self); - out[0] = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL); - *reinterpret_cast (mxGetPr(out[0])) = self; - } -} diff --git a/wrap/tests/expected_namespaces/new_ns1ClassB.m b/wrap/tests/expected_namespaces/new_ns1ClassB.m deleted file mode 100644 index b75d6b9bf..000000000 --- a/wrap/tests/expected_namespaces/new_ns1ClassB.m +++ /dev/null @@ -1,4 +0,0 @@ -% automatically generated by wrap -function result = new_ns1ClassB(obj) - error('need to compile new_ns1ClassB.cpp'); -end diff --git a/wrap/tests/expected_namespaces/new_ns2ClassA.cpp b/wrap/tests/expected_namespaces/new_ns2ClassA.cpp deleted file mode 100644 index 57faabc79..000000000 --- a/wrap/tests/expected_namespaces/new_ns2ClassA.cpp +++ /dev/null @@ -1,37 +0,0 @@ -// automatically generated by wrap -#include -#include -#include -typedef boost::shared_ptr Shared; - -static std::set collector; - -void cleanup(void) { - for(std::set::iterator iter = collector.begin(); iter != collector.end(); ) { - delete *iter; - collector.erase(iter++); - } -} -void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - mexAtExit(cleanup); - - const mxArray* input = in[0]; - Shared* self = *(Shared**) mxGetData(input); - - if(self) { - if(nargin > 1) { - collector.insert(self); - } - else if(collector.erase(self)) - delete self; - } else { - int nc = unwrap(in[1]); - - if(nc == 0) - self = new Shared(new ns2::ClassA()); - collector.insert(self); - out[0] = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL); - *reinterpret_cast (mxGetPr(out[0])) = self; - } -} diff --git a/wrap/tests/expected_namespaces/new_ns2ClassA.m b/wrap/tests/expected_namespaces/new_ns2ClassA.m deleted file mode 100644 index b3b9201d6..000000000 --- a/wrap/tests/expected_namespaces/new_ns2ClassA.m +++ /dev/null @@ -1,4 +0,0 @@ -% automatically generated by wrap -function result = new_ns2ClassA(obj) - error('need to compile new_ns2ClassA.cpp'); -end diff --git a/wrap/tests/expected_namespaces/new_ns2ClassC.cpp b/wrap/tests/expected_namespaces/new_ns2ClassC.cpp deleted file mode 100644 index e836a80fd..000000000 --- a/wrap/tests/expected_namespaces/new_ns2ClassC.cpp +++ /dev/null @@ -1,36 +0,0 @@ -// automatically generated by wrap -#include -#include -typedef boost::shared_ptr Shared; - -static std::set collector; - -void cleanup(void) { - for(std::set::iterator iter = collector.begin(); iter != collector.end(); ) { - delete *iter; - collector.erase(iter++); - } -} -void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - mexAtExit(cleanup); - - const mxArray* input = in[0]; - Shared* self = *(Shared**) mxGetData(input); - - if(self) { - if(nargin > 1) { - collector.insert(self); - } - else if(collector.erase(self)) - delete self; - } else { - int nc = unwrap(in[1]); - - if(nc == 0) - self = new Shared(new ns2::ClassC()); - collector.insert(self); - out[0] = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL); - *reinterpret_cast (mxGetPr(out[0])) = self; - } -} diff --git a/wrap/tests/expected_namespaces/new_ns2ClassC.m b/wrap/tests/expected_namespaces/new_ns2ClassC.m deleted file mode 100644 index 0f7ffb26f..000000000 --- a/wrap/tests/expected_namespaces/new_ns2ClassC.m +++ /dev/null @@ -1,4 +0,0 @@ -% automatically generated by wrap -function result = new_ns2ClassC(obj) - error('need to compile new_ns2ClassC.cpp'); -end diff --git a/wrap/tests/expected_namespaces/new_ns2ns3ClassB.cpp b/wrap/tests/expected_namespaces/new_ns2ns3ClassB.cpp deleted file mode 100644 index af1a25922..000000000 --- a/wrap/tests/expected_namespaces/new_ns2ns3ClassB.cpp +++ /dev/null @@ -1,37 +0,0 @@ -// automatically generated by wrap -#include -#include -#include -typedef boost::shared_ptr Shared; - -static std::set collector; - -void cleanup(void) { - for(std::set::iterator iter = collector.begin(); iter != collector.end(); ) { - delete *iter; - collector.erase(iter++); - } -} -void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - mexAtExit(cleanup); - - const mxArray* input = in[0]; - Shared* self = *(Shared**) mxGetData(input); - - if(self) { - if(nargin > 1) { - collector.insert(self); - } - else if(collector.erase(self)) - delete self; - } else { - int nc = unwrap(in[1]); - - if(nc == 0) - self = new Shared(new ns2::ns3::ClassB()); - collector.insert(self); - out[0] = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL); - *reinterpret_cast (mxGetPr(out[0])) = self; - } -} diff --git a/wrap/tests/expected_namespaces/new_ns2ns3ClassB.m b/wrap/tests/expected_namespaces/new_ns2ns3ClassB.m deleted file mode 100644 index 707e159f0..000000000 --- a/wrap/tests/expected_namespaces/new_ns2ns3ClassB.m +++ /dev/null @@ -1,4 +0,0 @@ -% automatically generated by wrap -function result = new_ns2ns3ClassB(obj) - error('need to compile new_ns2ns3ClassB.cpp'); -end diff --git a/wrap/tests/expected_namespaces/ns1ClassA.m b/wrap/tests/expected_namespaces/ns1ClassA.m new file mode 100644 index 000000000..29f48ab4e --- /dev/null +++ b/wrap/tests/expected_namespaces/ns1ClassA.m @@ -0,0 +1,31 @@ +% automatically generated by wrap +classdef ns1ClassA < handle + properties + ptr_ns1ClassA = 0 + end + methods + function obj = ns1ClassA(varargin) + if nargin == 2 && isa(varargin{1}, 'uint64') && varargin{1} == uint64(5139824614673773682) + my_ptr = varargin{2}; + testNamespaces_wrapper(0, my_ptr); + elseif nargin == 0 + my_ptr = testNamespaces_wrapper(1); + else + error('Arguments do not match any overload of ns1ClassA constructor'); + end + obj.ptr_ns1ClassA = my_ptr; + end + + function delete(obj) + testNamespaces_wrapper(2, obj.ptr_ns1ClassA); + end + + function display(obj), obj.print(''); end + + function disp(obj), obj.display; end + + end + + methods(Static = true) + end +end diff --git a/wrap/tests/expected_namespaces/ns1ClassB.m b/wrap/tests/expected_namespaces/ns1ClassB.m new file mode 100644 index 000000000..a1e9bc9a5 --- /dev/null +++ b/wrap/tests/expected_namespaces/ns1ClassB.m @@ -0,0 +1,31 @@ +% automatically generated by wrap +classdef ns1ClassB < handle + properties + ptr_ns1ClassB = 0 + end + methods + function obj = ns1ClassB(varargin) + if nargin == 2 && isa(varargin{1}, 'uint64') && varargin{1} == uint64(5139824614673773682) + my_ptr = varargin{2}; + testNamespaces_wrapper(3, my_ptr); + elseif nargin == 0 + my_ptr = testNamespaces_wrapper(4); + else + error('Arguments do not match any overload of ns1ClassB constructor'); + end + obj.ptr_ns1ClassB = my_ptr; + end + + function delete(obj) + testNamespaces_wrapper(5, obj.ptr_ns1ClassB); + end + + function display(obj), obj.print(''); end + + function disp(obj), obj.display; end + + end + + methods(Static = true) + end +end diff --git a/wrap/tests/expected_namespaces/ns2ClassA.m b/wrap/tests/expected_namespaces/ns2ClassA.m new file mode 100644 index 000000000..7b3df9ed6 --- /dev/null +++ b/wrap/tests/expected_namespaces/ns2ClassA.m @@ -0,0 +1,63 @@ +% automatically generated by wrap +classdef ns2ClassA < handle + properties + ptr_ns2ClassA = 0 + end + methods + function obj = ns2ClassA(varargin) + if nargin == 2 && isa(varargin{1}, 'uint64') && varargin{1} == uint64(5139824614673773682) + my_ptr = varargin{2}; + testNamespaces_wrapper(6, my_ptr); + elseif nargin == 0 + my_ptr = testNamespaces_wrapper(7); + else + error('Arguments do not match any overload of ns2ClassA constructor'); + end + obj.ptr_ns2ClassA = my_ptr; + end + + function delete(obj) + testNamespaces_wrapper(8, obj.ptr_ns2ClassA); + end + + function display(obj), obj.print(''); end + + function disp(obj), obj.display; end + + function varargout = memberFunction(this, varargin) + if length(varargin) == 0 + varargout{1} = testNamespaces_wrapper(9, this, varargin{:}); + else + error('Arguments do not match any overload of function ns2ClassA.memberFunction'); + end + end + + function varargout = nsArg(this, varargin) + if length(varargin) == 1 && isa(varargin{1},'ns1ClassB') + varargout{1} = testNamespaces_wrapper(10, this, varargin{:}); + else + error('Arguments do not match any overload of function ns2ClassA.nsArg'); + end + end + + function varargout = nsReturn(this, varargin) + if length(varargin) == 1 && isa(varargin{1},'double') + varargout{1} = testNamespaces_wrapper(11, this, varargin{:}); + else + error('Arguments do not match any overload of function ns2ClassA.nsReturn'); + end + end + + end + + methods(Static = true) + function varargout = Afunction(varargin) + if length(varargin) == 0 + varargout{1} = testNamespaces_wrapper(12, varargin{:}); + else + error('Arguments do not match any overload of function ns2ClassA.Afunction'); + end + end + + end +end diff --git a/wrap/tests/expected_namespaces/ns2ClassA_afunction.cpp b/wrap/tests/expected_namespaces/ns2ClassA_afunction.cpp deleted file mode 100644 index 6c903c946..000000000 --- a/wrap/tests/expected_namespaces/ns2ClassA_afunction.cpp +++ /dev/null @@ -1,12 +0,0 @@ -// automatically generated by wrap -#include -#include -#include -typedef boost::shared_ptr Shareddouble; -typedef boost::shared_ptr Shared; -void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("ns2ClassA_afunction",nargout,nargin,0); - double result = ns2::ClassA::afunction(); - out[0] = wrap< double >(result); -} diff --git a/wrap/tests/expected_namespaces/ns2ClassA_afunction.m b/wrap/tests/expected_namespaces/ns2ClassA_afunction.m deleted file mode 100644 index f41203ba1..000000000 --- a/wrap/tests/expected_namespaces/ns2ClassA_afunction.m +++ /dev/null @@ -1,5 +0,0 @@ -% automatically generated by wrap -function result = ns2ClassA_afunction() -% usage: x = ns2ClassA_afunction() - error('need to compile ns2ClassA_afunction.cpp'); -end diff --git a/wrap/tests/expected_namespaces/ns2ClassC.m b/wrap/tests/expected_namespaces/ns2ClassC.m new file mode 100644 index 000000000..5ba6e7125 --- /dev/null +++ b/wrap/tests/expected_namespaces/ns2ClassC.m @@ -0,0 +1,31 @@ +% automatically generated by wrap +classdef ns2ClassC < handle + properties + ptr_ns2ClassC = 0 + end + methods + function obj = ns2ClassC(varargin) + if nargin == 2 && isa(varargin{1}, 'uint64') && varargin{1} == uint64(5139824614673773682) + my_ptr = varargin{2}; + testNamespaces_wrapper(16, my_ptr); + elseif nargin == 0 + my_ptr = testNamespaces_wrapper(17); + else + error('Arguments do not match any overload of ns2ClassC constructor'); + end + obj.ptr_ns2ClassC = my_ptr; + end + + function delete(obj) + testNamespaces_wrapper(18, obj.ptr_ns2ClassC); + end + + function display(obj), obj.print(''); end + + function disp(obj), obj.display; end + + end + + methods(Static = true) + end +end diff --git a/wrap/tests/expected_namespaces/ns2ns3ClassB.m b/wrap/tests/expected_namespaces/ns2ns3ClassB.m new file mode 100644 index 000000000..b5e57ea19 --- /dev/null +++ b/wrap/tests/expected_namespaces/ns2ns3ClassB.m @@ -0,0 +1,31 @@ +% automatically generated by wrap +classdef ns2ns3ClassB < handle + properties + ptr_ns2ns3ClassB = 0 + end + methods + function obj = ns2ns3ClassB(varargin) + if nargin == 2 && isa(varargin{1}, 'uint64') && varargin{1} == uint64(5139824614673773682) + my_ptr = varargin{2}; + testNamespaces_wrapper(13, my_ptr); + elseif nargin == 0 + my_ptr = testNamespaces_wrapper(14); + else + error('Arguments do not match any overload of ns2ns3ClassB constructor'); + end + obj.ptr_ns2ns3ClassB = my_ptr; + end + + function delete(obj) + testNamespaces_wrapper(15, obj.ptr_ns2ns3ClassB); + end + + function display(obj), obj.print(''); end + + function disp(obj), obj.display; end + + end + + methods(Static = true) + end +end diff --git a/wrap/tests/expected_namespaces/testNamespaces_wrapper.cpp b/wrap/tests/expected_namespaces/testNamespaces_wrapper.cpp new file mode 100644 index 000000000..bdb0632d0 --- /dev/null +++ b/wrap/tests/expected_namespaces/testNamespaces_wrapper.cpp @@ -0,0 +1,395 @@ +// automatically generated by wrap +#include +#include +#include + +#include +#include +#include +#include +#include +#include + + +typedef std::set*> Collector_ns1ClassA; +static Collector_ns1ClassA collector_ns1ClassA; +typedef std::set*> Collector_ns1ClassB; +static Collector_ns1ClassB collector_ns1ClassB; +typedef std::set*> Collector_ns2ClassA; +static Collector_ns2ClassA collector_ns2ClassA; +typedef std::set*> Collector_ns2ns3ClassB; +static Collector_ns2ns3ClassB collector_ns2ns3ClassB; +typedef std::set*> Collector_ns2ClassC; +static Collector_ns2ClassC collector_ns2ClassC; +typedef std::set*> Collector_ClassD; +static Collector_ClassD collector_ClassD; + +void _deleteAllObjects() +{ + for(Collector_ns1ClassA::iterator iter = collector_ns1ClassA.begin(); + iter != collector_ns1ClassA.end(); ) { + delete *iter; + collector_ns1ClassA.erase(iter++); + } + for(Collector_ns1ClassB::iterator iter = collector_ns1ClassB.begin(); + iter != collector_ns1ClassB.end(); ) { + delete *iter; + collector_ns1ClassB.erase(iter++); + } + for(Collector_ns2ClassA::iterator iter = collector_ns2ClassA.begin(); + iter != collector_ns2ClassA.end(); ) { + delete *iter; + collector_ns2ClassA.erase(iter++); + } + for(Collector_ns2ns3ClassB::iterator iter = collector_ns2ns3ClassB.begin(); + iter != collector_ns2ns3ClassB.end(); ) { + delete *iter; + collector_ns2ns3ClassB.erase(iter++); + } + for(Collector_ns2ClassC::iterator iter = collector_ns2ClassC.begin(); + iter != collector_ns2ClassC.end(); ) { + delete *iter; + collector_ns2ClassC.erase(iter++); + } + for(Collector_ClassD::iterator iter = collector_ClassD.begin(); + iter != collector_ClassD.end(); ) { + delete *iter; + collector_ClassD.erase(iter++); + } +} + +static bool _RTTIRegister_testNamespaces_done = false; +void _testNamespaces_RTTIRegister() { + std::map types; + + mxArray *registry = mexGetVariable("global", "gtsamwrap_rttiRegistry"); + if(!registry) + registry = mxCreateStructMatrix(1, 1, 0, NULL); + typedef std::pair StringPair; + BOOST_FOREACH(const StringPair& rtti_matlab, types) { + int fieldId = mxAddField(registry, rtti_matlab.first.c_str()); + if(fieldId < 0) + mexErrMsgTxt("gtsam wrap: Error indexing RTTI types, inheritance will not work correctly"); + mxArray *matlabName = mxCreateString(rtti_matlab.second.c_str()); + mxSetFieldByNumber(registry, 0, fieldId, matlabName); + } + if(mexPutVariable("global", "gtsamwrap_rttiRegistry", registry) != 0) + mexErrMsgTxt("gtsam wrap: Error indexing RTTI types, inheritance will not work correctly"); + mxDestroyArray(registry); +} + +void ns1ClassA_collectorInsertAndMakeBase_0(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + mexAtExit(&_deleteAllObjects); + typedef boost::shared_ptr Shared; + + Shared *self = *reinterpret_cast (mxGetData(in[0])); + collector_ns1ClassA.insert(self); +} + +void ns1ClassA_constructor_1(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + mexAtExit(&_deleteAllObjects); + typedef boost::shared_ptr Shared; + + Shared *self = new Shared(new ns1::ClassA()); + collector_ns1ClassA.insert(self); + out[0] = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL); + *reinterpret_cast (mxGetData(out[0])) = self; +} + +void ns1ClassA_deconstructor_2(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + typedef boost::shared_ptr Shared; + checkArguments("delete_ns1ClassA",nargout,nargin,1); + Shared *self = *reinterpret_cast(mxGetData(in[0])); + Collector_ns1ClassA::iterator item; + item = collector_ns1ClassA.find(self); + if(item != collector_ns1ClassA.end()) { + delete self; + collector_ns1ClassA.erase(item); + } +} + +void ns1ClassB_collectorInsertAndMakeBase_3(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + mexAtExit(&_deleteAllObjects); + typedef boost::shared_ptr Shared; + + Shared *self = *reinterpret_cast (mxGetData(in[0])); + collector_ns1ClassB.insert(self); +} + +void ns1ClassB_constructor_4(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + mexAtExit(&_deleteAllObjects); + typedef boost::shared_ptr Shared; + + Shared *self = new Shared(new ns1::ClassB()); + collector_ns1ClassB.insert(self); + out[0] = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL); + *reinterpret_cast (mxGetData(out[0])) = self; +} + +void ns1ClassB_deconstructor_5(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + typedef boost::shared_ptr Shared; + checkArguments("delete_ns1ClassB",nargout,nargin,1); + Shared *self = *reinterpret_cast(mxGetData(in[0])); + Collector_ns1ClassB::iterator item; + item = collector_ns1ClassB.find(self); + if(item != collector_ns1ClassB.end()) { + delete self; + collector_ns1ClassB.erase(item); + } +} + +void ns2ClassA_collectorInsertAndMakeBase_6(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + mexAtExit(&_deleteAllObjects); + typedef boost::shared_ptr Shared; + + Shared *self = *reinterpret_cast (mxGetData(in[0])); + collector_ns2ClassA.insert(self); +} + +void ns2ClassA_constructor_7(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + mexAtExit(&_deleteAllObjects); + typedef boost::shared_ptr Shared; + + Shared *self = new Shared(new ns2::ClassA()); + collector_ns2ClassA.insert(self); + out[0] = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL); + *reinterpret_cast (mxGetData(out[0])) = self; +} + +void ns2ClassA_deconstructor_8(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + typedef boost::shared_ptr Shared; + checkArguments("delete_ns2ClassA",nargout,nargin,1); + Shared *self = *reinterpret_cast(mxGetData(in[0])); + Collector_ns2ClassA::iterator item; + item = collector_ns2ClassA.find(self); + if(item != collector_ns2ClassA.end()) { + delete self; + collector_ns2ClassA.erase(item); + } +} + +void ns2ClassA_memberFunction_9(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + typedef boost::shared_ptr Shared; + checkArguments("memberFunction",nargout,nargin-1,0); + Shared obj = unwrap_shared_ptr(in[0], "ptr_ns2ClassA"); + out[0] = wrap< double >(obj->memberFunction()); +} + +void ns2ClassA_nsArg_10(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + typedef boost::shared_ptr Shared; + checkArguments("nsArg",nargout,nargin-1,1); + Shared obj = unwrap_shared_ptr(in[0], "ptr_ns2ClassA"); + ns1::ClassB& arg = *unwrap_shared_ptr< ns1::ClassB >(in[1], "ptr_ns1ClassB"); + out[0] = wrap< int >(obj->nsArg(arg)); +} + +void ns2ClassA_nsReturn_11(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + typedef boost::shared_ptr SharedClassB; + typedef boost::shared_ptr Shared; + checkArguments("nsReturn",nargout,nargin-1,1); + Shared obj = unwrap_shared_ptr(in[0], "ptr_ns2ClassA"); + double q = unwrap< double >(in[1]); + out[0] = wrap_shared_ptr(SharedClassB(new ns2::ns3::ClassB(obj->nsReturn(q))),"ns2ns3ClassB", false); +} + +void ns2ClassA_afunction_12(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + typedef boost::shared_ptr Shared; + checkArguments("ns2ClassA.afunction",nargout,nargin,0); + out[0] = wrap< double >(ns2::ClassA::afunction()); +} + +void ns2ns3ClassB_collectorInsertAndMakeBase_13(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + mexAtExit(&_deleteAllObjects); + typedef boost::shared_ptr Shared; + + Shared *self = *reinterpret_cast (mxGetData(in[0])); + collector_ns2ns3ClassB.insert(self); +} + +void ns2ns3ClassB_constructor_14(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + mexAtExit(&_deleteAllObjects); + typedef boost::shared_ptr Shared; + + Shared *self = new Shared(new ns2::ns3::ClassB()); + collector_ns2ns3ClassB.insert(self); + out[0] = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL); + *reinterpret_cast (mxGetData(out[0])) = self; +} + +void ns2ns3ClassB_deconstructor_15(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + typedef boost::shared_ptr Shared; + checkArguments("delete_ns2ns3ClassB",nargout,nargin,1); + Shared *self = *reinterpret_cast(mxGetData(in[0])); + Collector_ns2ns3ClassB::iterator item; + item = collector_ns2ns3ClassB.find(self); + if(item != collector_ns2ns3ClassB.end()) { + delete self; + collector_ns2ns3ClassB.erase(item); + } +} + +void ns2ClassC_collectorInsertAndMakeBase_16(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + mexAtExit(&_deleteAllObjects); + typedef boost::shared_ptr Shared; + + Shared *self = *reinterpret_cast (mxGetData(in[0])); + collector_ns2ClassC.insert(self); +} + +void ns2ClassC_constructor_17(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + mexAtExit(&_deleteAllObjects); + typedef boost::shared_ptr Shared; + + Shared *self = new Shared(new ns2::ClassC()); + collector_ns2ClassC.insert(self); + out[0] = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL); + *reinterpret_cast (mxGetData(out[0])) = self; +} + +void ns2ClassC_deconstructor_18(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + typedef boost::shared_ptr Shared; + checkArguments("delete_ns2ClassC",nargout,nargin,1); + Shared *self = *reinterpret_cast(mxGetData(in[0])); + Collector_ns2ClassC::iterator item; + item = collector_ns2ClassC.find(self); + if(item != collector_ns2ClassC.end()) { + delete self; + collector_ns2ClassC.erase(item); + } +} + +void ClassD_collectorInsertAndMakeBase_19(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + mexAtExit(&_deleteAllObjects); + typedef boost::shared_ptr Shared; + + Shared *self = *reinterpret_cast (mxGetData(in[0])); + collector_ClassD.insert(self); +} + +void ClassD_constructor_20(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + mexAtExit(&_deleteAllObjects); + typedef boost::shared_ptr Shared; + + Shared *self = new Shared(new ClassD()); + collector_ClassD.insert(self); + out[0] = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL); + *reinterpret_cast (mxGetData(out[0])) = self; +} + +void ClassD_deconstructor_21(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + typedef boost::shared_ptr Shared; + checkArguments("delete_ClassD",nargout,nargin,1); + Shared *self = *reinterpret_cast(mxGetData(in[0])); + Collector_ClassD::iterator item; + item = collector_ClassD.find(self); + if(item != collector_ClassD.end()) { + delete self; + collector_ClassD.erase(item); + } +} + + +void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + mstream mout; + std::streambuf *outbuf = std::cout.rdbuf(&mout); + + if(!_RTTIRegister_testNamespaces_done) { + _testNamespaces_RTTIRegister(); + _RTTIRegister_testNamespaces_done = true; + } + int id = unwrap(in[0]); + + switch(id) { + case 0: + ns1ClassA_collectorInsertAndMakeBase_0(nargout, out, nargin-1, in+1); + break; + case 1: + ns1ClassA_constructor_1(nargout, out, nargin-1, in+1); + break; + case 2: + ns1ClassA_deconstructor_2(nargout, out, nargin-1, in+1); + break; + case 3: + ns1ClassB_collectorInsertAndMakeBase_3(nargout, out, nargin-1, in+1); + break; + case 4: + ns1ClassB_constructor_4(nargout, out, nargin-1, in+1); + break; + case 5: + ns1ClassB_deconstructor_5(nargout, out, nargin-1, in+1); + break; + case 6: + ns2ClassA_collectorInsertAndMakeBase_6(nargout, out, nargin-1, in+1); + break; + case 7: + ns2ClassA_constructor_7(nargout, out, nargin-1, in+1); + break; + case 8: + ns2ClassA_deconstructor_8(nargout, out, nargin-1, in+1); + break; + case 9: + ns2ClassA_memberFunction_9(nargout, out, nargin-1, in+1); + break; + case 10: + ns2ClassA_nsArg_10(nargout, out, nargin-1, in+1); + break; + case 11: + ns2ClassA_nsReturn_11(nargout, out, nargin-1, in+1); + break; + case 12: + ns2ClassA_afunction_12(nargout, out, nargin-1, in+1); + break; + case 13: + ns2ns3ClassB_collectorInsertAndMakeBase_13(nargout, out, nargin-1, in+1); + break; + case 14: + ns2ns3ClassB_constructor_14(nargout, out, nargin-1, in+1); + break; + case 15: + ns2ns3ClassB_deconstructor_15(nargout, out, nargin-1, in+1); + break; + case 16: + ns2ClassC_collectorInsertAndMakeBase_16(nargout, out, nargin-1, in+1); + break; + case 17: + ns2ClassC_constructor_17(nargout, out, nargin-1, in+1); + break; + case 18: + ns2ClassC_deconstructor_18(nargout, out, nargin-1, in+1); + break; + case 19: + ClassD_collectorInsertAndMakeBase_19(nargout, out, nargin-1, in+1); + break; + case 20: + ClassD_constructor_20(nargout, out, nargin-1, in+1); + break; + case 21: + ClassD_deconstructor_21(nargout, out, nargin-1, in+1); + break; + } + + std::cout.rdbuf(outbuf); +} diff --git a/wrap/tests/testDependencies.h b/wrap/tests/testDependencies.h index 429bb5a2a..34a8056b8 100644 --- a/wrap/tests/testDependencies.h +++ b/wrap/tests/testDependencies.h @@ -1,24 +1,8 @@ //Header file to test dependency checking // class Pose3 { - Pose3(); - Pose3(const Rot3& r, const Point3& t);//What is Rot3? Throw here - Pose3(Vector v); - Pose3(Matrix t); - static Pose3 Expmap(Vector v); - static Vector Logmap(const Pose3& p); - static Rot3 testStaticDep(Rot3& r);//What is Rot3? Throw here - void print(string s) const; - bool equals(const Pose3& pose, double tol) const; - double x() const; - double y() const; - double z() const; - Rot3 testReturnType() const; // Throw here - Matrix matrix() const; - Matrix adjointMap() const; - Pose3 compose(const Pose3& p2); - Pose3 between(const Pose3& p2); - Pose3 retract(Vector v); - Point3 translation() const; - Rot3 rotation() const; //What is Rot3? Throw here + Pose3(const Rot3& r, const Point3& t); //What is Rot3? Throw here + static Rot3 testStaticDep(Rot3& r); //What is Rot3? Throw here + Rot3 testReturnType() const; // Throw here + void testMethodArg(const Rot3& r) const; }; diff --git a/wrap/tests/testWrap.cpp b/wrap/tests/testWrap.cpp index 2a0b5e259..b8e9effc1 100644 --- a/wrap/tests/testWrap.cpp +++ b/wrap/tests/testWrap.cpp @@ -58,16 +58,16 @@ TEST( wrap, ArgumentList ) { } /* ************************************************************************* */ -TEST( wrap, check_exception ) { +TEST_UNSAFE( wrap, check_exception ) { THROWS_EXCEPTION(Module("/notarealpath", "geometry",enable_verbose)); CHECK_EXCEPTION(Module("/alsonotarealpath", "geometry",enable_verbose), CantOpenFile); // clean out previous generated code - fs::remove_all("actual_deps"); + fs::remove_all("actual_deps"); string path = topdir + "/wrap/tests"; Module module(path.c_str(), "testDependencies",enable_verbose); - CHECK_EXCEPTION(module.matlab_code("mex", "actual_deps", "mexa64", headerPath, "-O5"), DependencyMissing); + CHECK_EXCEPTION(module.matlab_code("actual_deps", headerPath), DependencyMissing); } /* ************************************************************************* */ @@ -80,8 +80,9 @@ TEST( wrap, parse ) { strvec exp_using1, exp_using2; exp_using2 += "geometry"; // forward declarations - strvec exp_forward; exp_forward += "VectorNotEigen", "ns::OtherClass"; - EXPECT(assert_equal(exp_forward, module.forward_declarations)); + LONGS_EQUAL(2, module.forward_declarations.size()); + EXPECT(assert_equal("VectorNotEigen", module.forward_declarations[0].name)); + EXPECT(assert_equal("ns::OtherClass", module.forward_declarations[1].name)); // check first class, Point2 { @@ -116,10 +117,13 @@ TEST( wrap, parse ) { EXPECT(assert_equal("x", a1.name)); // check method - Method m1 = cls.methods.front(); - EXPECT(assert_equal("double", m1.returnVal.type1)); + CHECK(cls.methods.find("norm") != cls.methods.end()); + Method m1 = cls.methods.find("norm")->second; + LONGS_EQUAL(1, m1.returnVals.size()); + EXPECT(assert_equal("double", m1.returnVals.front().type1)); EXPECT(assert_equal("norm", m1.name)); - EXPECT_LONGS_EQUAL(0, m1.args.size()); + LONGS_EQUAL(1, m1.argLists.size()); + EXPECT_LONGS_EQUAL(0, m1.argLists.front().size()); EXPECT(m1.is_const_); } @@ -136,10 +140,12 @@ TEST( wrap, parse ) { EXPECT(assert_equal(exp_includes, testCls.includes)); // function to parse: pair return_pair (Vector v, Matrix A) const; - Method m2 = testCls.methods.front(); - EXPECT(m2.returnVal.isPair); - EXPECT(m2.returnVal.category1 == ReturnValue::EIGEN); - EXPECT(m2.returnVal.category2 == ReturnValue::EIGEN); + CHECK(testCls.methods.find("return_pair") != testCls.methods.end()); + Method m2 = testCls.methods.find("return_pair")->second; + LONGS_EQUAL(1, m2.returnVals.size()); + EXPECT(m2.returnVals.front().isPair); + EXPECT(m2.returnVals.front().category1 == ReturnValue::EIGEN); + EXPECT(m2.returnVals.front().category2 == ReturnValue::EIGEN); } } @@ -202,7 +208,6 @@ TEST( wrap, parse_namespaces ) { strvec exp_includes; exp_includes += ""; EXPECT(assert_equal(exp_includes, cls.includes)); } - } /* ************************************************************************* */ @@ -213,38 +218,21 @@ TEST( wrap, matlab_code_namespaces ) { string path = topdir + "/wrap"; // clean out previous generated code - fs::remove_all("actual_namespaces"); + fs::remove_all("actual_namespaces"); // emit MATLAB code - string exp_path = path + "/tests/expected_namespaces/"; - string act_path = "actual_namespaces/"; - module.matlab_code("mex", "actual_namespaces", "mexa64", headerPath, "-O5"); + string exp_path = path + "/tests/expected_namespaces/"; + string act_path = "actual_namespaces/"; + module.matlab_code("actual_namespaces", headerPath); - EXPECT(files_equal(exp_path + "new_ClassD.cpp" , act_path + "new_ClassD.cpp" )); - EXPECT(files_equal(exp_path + "new_ClassD.m" , act_path + "new_ClassD.m" )); - EXPECT(files_equal(exp_path + "new_ns1ClassA.cpp" , act_path + "new_ns1ClassA.cpp" )); - EXPECT(files_equal(exp_path + "new_ns1ClassA.m" , act_path + "new_ns1ClassA.m" )); - EXPECT(files_equal(exp_path + "new_ns1ClassB.cpp" , act_path + "new_ns1ClassB.cpp" )); - EXPECT(files_equal(exp_path + "new_ns1ClassB.m" , act_path + "new_ns1ClassB.m" )); - EXPECT(files_equal(exp_path + "new_ns2ClassA.cpp" , act_path + "new_ns2ClassA.cpp" )); - EXPECT(files_equal(exp_path + "new_ns2ClassA.m" , act_path + "new_ns2ClassA.m" )); - EXPECT(files_equal(exp_path + "new_ns2ClassC.cpp" , act_path + "new_ns2ClassC.cpp" )); - EXPECT(files_equal(exp_path + "new_ns2ClassC.m" , act_path + "new_ns2ClassC.m" )); - EXPECT(files_equal(exp_path + "new_ns2ns3ClassB.cpp" , act_path + "new_ns2ns3ClassB.cpp" )); - EXPECT(files_equal(exp_path + "new_ns2ns3ClassB.m" , act_path + "new_ns2ns3ClassB.m" )); - EXPECT(files_equal(exp_path + "ns2ClassA_afunction.cpp" , act_path + "ns2ClassA_afunction.cpp" )); - EXPECT(files_equal(exp_path + "ns2ClassA_afunction.m" , act_path + "ns2ClassA_afunction.m" )); - EXPECT(files_equal(exp_path + "@ns2ClassA/memberFunction.cpp", act_path + "@ns2ClassA/memberFunction.cpp")); - EXPECT(files_equal(exp_path + "@ns2ClassA/memberFunction.m" , act_path + "@ns2ClassA/memberFunction.m" )); - EXPECT(files_equal(exp_path + "@ns2ClassA/ns2ClassA.m" , act_path + "@ns2ClassA/ns2ClassA.m" )); - EXPECT(files_equal(exp_path + "@ns2ClassA/nsArg.cpp" , act_path + "@ns2ClassA/nsArg.cpp" )); - EXPECT(files_equal(exp_path + "@ns2ClassA/nsArg.m" , act_path + "@ns2ClassA/nsArg.m" )); - EXPECT(files_equal(exp_path + "@ns2ClassA/nsReturn.cpp" , act_path + "@ns2ClassA/nsReturn.cpp" )); - EXPECT(files_equal(exp_path + "@ns2ClassA/nsReturn.m" , act_path + "@ns2ClassA/nsReturn.m" )); - - EXPECT(files_equal(exp_path + "make_testNamespaces.m", act_path + "make_testNamespaces.m")); - EXPECT(files_equal(exp_path + "Makefile" , act_path + "Makefile" )); + EXPECT(files_equal(exp_path + "ClassD.m" , act_path + "ClassD.m" )); + EXPECT(files_equal(exp_path + "ns1ClassA.m" , act_path + "ns1ClassA.m" )); + EXPECT(files_equal(exp_path + "ns1ClassB.m" , act_path + "ns1ClassB.m" )); + EXPECT(files_equal(exp_path + "ns2ClassA.m" , act_path + "ns2ClassA.m" )); + EXPECT(files_equal(exp_path + "ns2ClassC.m" , act_path + "ns2ClassC.m" )); + EXPECT(files_equal(exp_path + "ns2ns3ClassB.m" , act_path + "ns2ns3ClassB.m" )); + EXPECT(files_equal(exp_path + "testNamespaces_wrapper.cpp" , act_path + "testNamespaces_wrapper.cpp" )); } /* ************************************************************************* */ @@ -255,87 +243,18 @@ TEST( wrap, matlab_code ) { string path = topdir + "/wrap"; // clean out previous generated code - fs::remove_all("actual"); + fs::remove_all("actual"); // emit MATLAB code // make_geometry will not compile, use make testwrap to generate real make - module.matlab_code("mex", "actual", "mexa64", headerPath, "-O5"); - string epath = path + "/tests/expected/"; - string apath = "actual/"; - - EXPECT(files_equal(epath + "Makefile" , apath + "Makefile" )); - EXPECT(files_equal(epath + "make_geometry.m" , apath + "make_geometry.m" )); - EXPECT(files_equal(epath + "new_Point2.cpp" , apath + "new_Point2.cpp" )); - EXPECT(files_equal(epath + "new_Point2.m" , apath + "new_Point2.m" )); - EXPECT(files_equal(epath + "new_Point3.cpp" , apath + "new_Point3.cpp" )); - EXPECT(files_equal(epath + "new_Point3.m" , apath + "new_Point3.m" )); - EXPECT(files_equal(epath + "new_Test.cpp" , apath + "new_Test.cpp" )); - EXPECT(files_equal(epath + "new_Test.m" , apath + "new_Test.m" )); - - EXPECT(files_equal(epath + "Point3_staticFunction.cpp" , apath + "Point3_staticFunction.cpp" )); - EXPECT(files_equal(epath + "Point3_staticFunction.m" , apath + "Point3_staticFunction.m" )); - EXPECT(files_equal(epath + "Point3_StaticFunctionRet.cpp" , apath + "Point3_StaticFunctionRet.cpp" )); - EXPECT(files_equal(epath + "Point3_StaticFunctionRet.m" , apath + "Point3_StaticFunctionRet.m" )); - - EXPECT(files_equal(epath + "@Point2/argChar.cpp" , apath + "@Point2/argChar.cpp" )); - EXPECT(files_equal(epath + "@Point2/argChar.m" , apath + "@Point2/argChar.m" )); - EXPECT(files_equal(epath + "@Point2/argUChar.cpp" , apath + "@Point2/argUChar.cpp" )); - EXPECT(files_equal(epath + "@Point2/argUChar.m" , apath + "@Point2/argUChar.m" )); - EXPECT(files_equal(epath + "@Point2/dim.cpp" , apath + "@Point2/dim.cpp" )); - EXPECT(files_equal(epath + "@Point2/dim.m" , apath + "@Point2/dim.m" )); - EXPECT(files_equal(epath + "@Point2/Point2.m" , apath + "@Point2/Point2.m" )); - EXPECT(files_equal(epath + "@Point2/returnChar.cpp" , apath + "@Point2/returnChar.cpp" )); - EXPECT(files_equal(epath + "@Point2/returnChar.m" , apath + "@Point2/returnChar.m" )); - EXPECT(files_equal(epath + "@Point2/vectorConfusion.cpp" , apath + "@Point2/vectorConfusion.cpp" )); - EXPECT(files_equal(epath + "@Point2/vectorConfusion.m" , apath + "@Point2/vectorConfusion.m" )); - EXPECT(files_equal(epath + "@Point2/x.cpp" , apath + "@Point2/x.cpp" )); - EXPECT(files_equal(epath + "@Point2/x.m" , apath + "@Point2/x.m" )); - EXPECT(files_equal(epath + "@Point2/y.cpp" , apath + "@Point2/y.cpp" )); - EXPECT(files_equal(epath + "@Point2/y.m" , apath + "@Point2/y.m" )); - EXPECT(files_equal(epath + "@Point3/norm.cpp" , apath + "@Point3/norm.cpp" )); - EXPECT(files_equal(epath + "@Point3/norm.m" , apath + "@Point3/norm.m" )); - EXPECT(files_equal(epath + "@Point3/Point3.m" , apath + "@Point3/Point3.m" )); - - EXPECT(files_equal(epath + "@Test/arg_EigenConstRef.cpp" , apath + "@Test/arg_EigenConstRef.cpp" )); - EXPECT(files_equal(epath + "@Test/arg_EigenConstRef.m" , apath + "@Test/arg_EigenConstRef.m" )); - EXPECT(files_equal(epath + "@Test/create_MixedPtrs.cpp" , apath + "@Test/create_MixedPtrs.cpp" )); - EXPECT(files_equal(epath + "@Test/create_MixedPtrs.m" , apath + "@Test/create_MixedPtrs.m" )); - EXPECT(files_equal(epath + "@Test/create_ptrs.cpp" , apath + "@Test/create_ptrs.cpp" )); - EXPECT(files_equal(epath + "@Test/create_ptrs.m" , apath + "@Test/create_ptrs.m" )); - EXPECT(files_equal(epath + "@Test/print.cpp" , apath + "@Test/print.cpp" )); - EXPECT(files_equal(epath + "@Test/print.m" , apath + "@Test/print.m" )); - EXPECT(files_equal(epath + "@Test/return_bool.cpp" , apath + "@Test/return_bool.cpp" )); - EXPECT(files_equal(epath + "@Test/return_bool.m" , apath + "@Test/return_bool.m" )); - EXPECT(files_equal(epath + "@Test/return_double.cpp" , apath + "@Test/return_double.cpp" )); - EXPECT(files_equal(epath + "@Test/return_double.m" , apath + "@Test/return_double.m" )); - EXPECT(files_equal(epath + "@Test/return_field.cpp" , apath + "@Test/return_field.cpp" )); - EXPECT(files_equal(epath + "@Test/return_field.m" , apath + "@Test/return_field.m" )); - EXPECT(files_equal(epath + "@Test/return_int.cpp" , apath + "@Test/return_int.cpp" )); - EXPECT(files_equal(epath + "@Test/return_int.m" , apath + "@Test/return_int.m" )); - EXPECT(files_equal(epath + "@Test/return_matrix1.cpp" , apath + "@Test/return_matrix1.cpp" )); - EXPECT(files_equal(epath + "@Test/return_matrix1.m" , apath + "@Test/return_matrix1.m" )); - EXPECT(files_equal(epath + "@Test/return_matrix2.cpp" , apath + "@Test/return_matrix2.cpp" )); - EXPECT(files_equal(epath + "@Test/return_matrix2.m" , apath + "@Test/return_matrix2.m" )); - EXPECT(files_equal(epath + "@Test/return_pair.cpp" , apath + "@Test/return_pair.cpp" )); - EXPECT(files_equal(epath + "@Test/return_pair.m" , apath + "@Test/return_pair.m" )); - EXPECT(files_equal(epath + "@Test/return_Point2Ptr.cpp" , apath + "@Test/return_Point2Ptr.cpp" )); - EXPECT(files_equal(epath + "@Test/return_Point2Ptr.m" , apath + "@Test/return_Point2Ptr.m" )); - EXPECT(files_equal(epath + "@Test/return_ptrs.cpp" , apath + "@Test/return_ptrs.cpp" )); - EXPECT(files_equal(epath + "@Test/return_ptrs.m" , apath + "@Test/return_ptrs.m" )); - EXPECT(files_equal(epath + "@Test/return_size_t.cpp" , apath + "@Test/return_size_t.cpp" )); - EXPECT(files_equal(epath + "@Test/return_size_t.m" , apath + "@Test/return_size_t.m" )); - EXPECT(files_equal(epath + "@Test/return_string.cpp" , apath + "@Test/return_string.cpp" )); - EXPECT(files_equal(epath + "@Test/return_string.m" , apath + "@Test/return_string.m" )); - EXPECT(files_equal(epath + "@Test/return_Test.cpp" , apath + "@Test/return_Test.cpp" )); - EXPECT(files_equal(epath + "@Test/return_Test.m" , apath + "@Test/return_Test.m" )); - EXPECT(files_equal(epath + "@Test/return_TestPtr.cpp" , apath + "@Test/return_TestPtr.cpp" )); - EXPECT(files_equal(epath + "@Test/return_TestPtr.m" , apath + "@Test/return_TestPtr.m" )); - EXPECT(files_equal(epath + "@Test/return_vector1.cpp" , apath + "@Test/return_vector1.cpp" )); - EXPECT(files_equal(epath + "@Test/return_vector1.m" , apath + "@Test/return_vector1.m" )); - EXPECT(files_equal(epath + "@Test/return_vector2.cpp" , apath + "@Test/return_vector2.cpp" )); - EXPECT(files_equal(epath + "@Test/return_vector2.m" , apath + "@Test/return_vector2.m" )); - EXPECT(files_equal(epath + "@Test/Test.m" , apath + "@Test/Test.m" )); + module.matlab_code("actual", headerPath); + string epath = path + "/tests/expected/"; + string apath = "actual/"; + EXPECT(files_equal(epath + "geometry_wrapper.cpp" , apath + "geometry_wrapper.cpp" )); + EXPECT(files_equal(epath + "Point2.m" , apath + "Point2.m" )); + EXPECT(files_equal(epath + "Point3.m" , apath + "Point3.m" )); + EXPECT(files_equal(epath + "Test.m" , apath + "Test.m" )); } /* ************************************************************************* */ diff --git a/wrap/utilities.cpp b/wrap/utilities.cpp index 9d56ec5cd..9c5d93c76 100644 --- a/wrap/utilities.cpp +++ b/wrap/utilities.cpp @@ -13,6 +13,7 @@ * @file utilities.ccp * @author Frank Dellaert * @author Andrew Melim + * @author Richard Roberts **/ #include @@ -121,21 +122,21 @@ void generateUsingNamespace(FileWriter& file, const vector& using_namesp } /* ************************************************************************* */ -void generateIncludes(FileWriter& file, const string& class_name, - const vector& includes) { - file.oss << "#include " << endl; - bool added_include = false; - BOOST_FOREACH(const string& s, includes) { - if (!s.empty()) { - file.oss << "#include <" << s << ">" << endl; - added_include = true; - } +string qualifiedName(const string& separator, const vector& names, const string& finalName) { + string result; + if(!names.empty()) { + for(size_t i = 0; i < names.size() - 1; ++i) + result += (names[i] + separator); + if(finalName.empty()) + result += names.back(); + else + result += (names.back() + separator + finalName); + } else if(!finalName.empty()) { + result = finalName; } - if (!added_include) // add default include - file.oss << "#include <" << class_name << ".h>" << endl; + return result; } /* ************************************************************************* */ - } // \namespace wrap diff --git a/wrap/utilities.h b/wrap/utilities.h index 1eb0e249f..0a252484f 100644 --- a/wrap/utilities.h +++ b/wrap/utilities.h @@ -13,6 +13,7 @@ * @file utilities.h * @author Frank Dellaert * @author Andrew Melim + * @author Richard Roberts **/ #pragma once @@ -21,6 +22,11 @@ #include #include #include +//#include // on Linux GCC: fails with error regarding needing C++0x std flags +//#include // same failure as above +#include // works on Linux GCC +#include +#include #include "FileWriter.h" @@ -28,44 +34,64 @@ namespace wrap { class CantOpenFile : public std::exception { private: - std::string filename_; + const std::string what_; public: - CantOpenFile(const std::string& filename) : filename_(filename) {} + CantOpenFile(const std::string& filename) : what_("Can't open file " + filename) {} ~CantOpenFile() throw() {} - virtual const char* what() const throw() { - return ("Can't open file " + filename_).c_str(); - } + virtual const char* what() const throw() { return what_.c_str(); } }; class ParseFailed : public std::exception { private: - int length_; + const std::string what_; public: - ParseFailed(int length) : length_(length) {} - ~ParseFailed() throw() {} - virtual const char* what() const throw() { - std::stringstream buf; - int len = length_+1; - buf << "Parse failed at character [" << len << "]"; - return buf.str().c_str(); - } + ParseFailed(int length) : what_((boost::format("Parse failed at character [%d]")%(length-1)).str()) {} + ~ParseFailed() throw() {} + virtual const char* what() const throw() { return what_.c_str(); } }; class DependencyMissing : public std::exception { private: - std::string dependency_; - std::string location_; + const std::string what_; public: - DependencyMissing(const std::string& dep, const std::string& loc) { - dependency_ = dep; - location_ = loc; - } + DependencyMissing(const std::string& dep, const std::string& loc) : + what_("Missing dependency " + dep + " in " + loc) {} ~DependencyMissing() throw() {} - virtual const char* what() const throw() { - return ("Missing dependency " + dependency_ + " in " + location_).c_str(); - } + virtual const char* what() const throw() { return what_.c_str(); } }; +class DuplicateDefinition : public std::exception { +private: + const std::string what_; +public: + DuplicateDefinition(const std::string& name) : + what_("Duplicate definition of " + name) {} + ~DuplicateDefinition() throw() {} + virtual const char* what() const throw() { return what_.c_str(); } +}; + +class AttributeError : public std::exception { +private: + const std::string what_; +public: + AttributeError(const std::string& name, const std::string& problem) : + what_("Class " + name + ": " + problem) {} + ~AttributeError() throw() {} + virtual const char* what() const throw() { return what_.c_str(); } +}; + +// "Unique" key to signal calling the matlab object constructor with a raw pointer +// to a shared pointer of the same C++ object type as the MATLAB type. +// Also present in matlab.h +static const uint64_t ptr_constructor_key = + (uint64_t('G') << 56) | + (uint64_t('T') << 48) | + (uint64_t('S') << 40) | + (uint64_t('A') << 32) | + (uint64_t('M') << 24) | + (uint64_t('p') << 16) | + (uint64_t('t') << 8) | + (uint64_t('r')); /** * read contents of a file into a std::string @@ -93,9 +119,9 @@ std::string maybe_shared_ptr(bool add, const std::string& qtype, const std::stri void generateUsingNamespace(FileWriter& file, const std::vector& using_namespaces); /** - * Creates the #include statements + * Return a qualified name, if finalName is empty, only the names vector will + * be used (i.e. there won't be a trailing separator on the qualified name). */ -void generateIncludes(FileWriter& file, const std::string& class_name, - const std::vector& includes); +std::string qualifiedName(const std::string& separator, const std::vector& names, const std::string& finalName = ""); } // \namespace wrap diff --git a/wrap/wrap.cpp b/wrap/wrap.cpp index f818094f7..05763d892 100644 --- a/wrap/wrap.cpp +++ b/wrap/wrap.cpp @@ -24,42 +24,33 @@ using namespace std; /** * Top-level function to wrap a module - * @param mexCommand is a sufficiently qualified command to execute mex within a makefile - * @param mexExt is the extension for mex binaries for this os/cpu * @param interfacePath path to where interface file lives, e.g., borg/gtsam * @param moduleName name of the module to be generated e.g. gtsam * @param toolboxPath path where the toolbox should be generated, e.g. borg/gtsam/build * @param headerPath is the path to matlab.h - * @param mexFlags extra arguments for mex script, i.e., include flags etc... */ void generate_matlab_toolbox( - const string& mexCommand, - const string& mexExt, const string& interfacePath, const string& moduleName, const string& toolboxPath, - const string& headerPath, - const string& mexFlags) + const string& headerPath) { // Parse interface file into class object // This recursively creates Class objects, Method objects, etc... wrap::Module module(interfacePath, moduleName, false); // Then emit MATLAB code - module.matlab_code(mexCommand,toolboxPath,mexExt,headerPath,mexFlags); + module.matlab_code(toolboxPath,headerPath); } /** Displays usage information */ void usage() { cerr << "wrap parses an interface file and produces a MATLAB toolbox" << endl; - cerr << "usage: wrap mexExecutable mexExtension interfacePath moduleName toolboxPath [mexFlags]" << endl; - cerr << " mexExecutable : command to execute mex if on path, use 'mex'" << endl; - cerr << " mexExtension : OS/CPU-dependent extension for MEX binaries" << endl; + cerr << "usage: wrap interfacePath moduleName toolboxPath headerPath" << endl; cerr << " interfacePath : *absolute* path to directory of module interface file" << endl; cerr << " moduleName : the name of the module, interface file must be called moduleName.h" << endl; cerr << " toolboxPath : the directory in which to generate the wrappers" << endl; cerr << " headerPath : path to matlab.h" << endl; - cerr << " [mexFlags] : extra flags for the mex command" << endl; } /** @@ -67,7 +58,7 @@ void usage() { * Typically called from "make all" using appropriate arguments */ int main(int argc, const char* argv[]) { - if (argc<7 || argc>8) { + if (argc != 5) { cerr << "Invalid arguments:\n"; for (int i=0; i