Merging updates from new_wrap branch back into trunk

release/4.3a0
Alex Cunningham 2012-07-01 18:24:48 +00:00
commit 735d927189
131 changed files with 1138 additions and 815 deletions

View File

@ -281,6 +281,7 @@
</profile>
</scannerConfigBuildInfo>
</storageModule>
<storageModule moduleId="org.eclipse.cdt.internal.ui.text.commentOwnerProjectMappings"/>
<storageModule moduleId="org.eclipse.cdt.make.core.buildtargets">
<buildTargets>
<target name="check" path="build/base" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
@ -1011,6 +1012,14 @@
<useDefaultCommand>true</useDefaultCommand>
<runAllBuilders>true</runAllBuilders>
</target>
<target name="all" path="build/wrap/gtsam" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
<buildCommand>make</buildCommand>
<buildArguments>-j5</buildArguments>
<buildTarget>all</buildTarget>
<stopOnError>true</stopOnError>
<useDefaultCommand>true</useDefaultCommand>
<runAllBuilders>true</runAllBuilders>
</target>
<target name="all" path="linear" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
<buildCommand>make</buildCommand>
<buildArguments>-j2</buildArguments>
@ -2166,6 +2175,38 @@
<useDefaultCommand>true</useDefaultCommand>
<runAllBuilders>true</runAllBuilders>
</target>
<target name="wrap_gtsam_clean" path="" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
<buildCommand>make</buildCommand>
<buildArguments>-j5</buildArguments>
<buildTarget>wrap_gtsam_clean</buildTarget>
<stopOnError>true</stopOnError>
<useDefaultCommand>true</useDefaultCommand>
<runAllBuilders>true</runAllBuilders>
</target>
<target name="wrap_gtsam_unstable_clean" path="" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
<buildCommand>make</buildCommand>
<buildArguments>-j5</buildArguments>
<buildTarget>wrap_gtsam_unstable_clean</buildTarget>
<stopOnError>true</stopOnError>
<useDefaultCommand>true</useDefaultCommand>
<runAllBuilders>true</runAllBuilders>
</target>
<target name="wrap_gtsam_distclean" path="" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
<buildCommand>make</buildCommand>
<buildArguments>-j5</buildArguments>
<buildTarget>wrap_gtsam_distclean</buildTarget>
<stopOnError>true</stopOnError>
<useDefaultCommand>true</useDefaultCommand>
<runAllBuilders>true</runAllBuilders>
</target>
<target name="wrap_gtsam_unstable_distclean" path="" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
<buildCommand>make</buildCommand>
<buildArguments>-j5</buildArguments>
<buildTarget>wrap_gtsam_unstable_distclean</buildTarget>
<stopOnError>true</stopOnError>
<useDefaultCommand>true</useDefaultCommand>
<runAllBuilders>true</runAllBuilders>
</target>
<target name="testRot3.run" path="geometry" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
<buildCommand>make</buildCommand>
<buildArguments>-j2</buildArguments>

View File

@ -63,6 +63,7 @@ option(GTSAM_INSTALL_MATLAB_TESTS "Enable/Disable installation of matlab
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")
# TODO: Check for matlab mex binary before handling building of binaries

View File

@ -138,6 +138,5 @@ if (GTSAM_BUILD_WRAP)
# 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
# FIXME: rework install commands to specify only certain filetypes/folders to avoid installing temp files
wrap_library(gtsam "${mexFlags}" "../")
endif ()

View File

@ -33,6 +33,10 @@ namespace gtsam {
std::cout << s << "Dummy " << id << std::endl;
}
unsigned char dummyTwoVar(unsigned char a) const {
return a;
}
};
} // namespace gtsam

View File

@ -14,6 +14,7 @@ namespace gtsam {
class Dummy {
Dummy();
void print(string s) const;
unsigned char dummyTwoVar(unsigned char a) const;
};
#include <gtsam_unstable/dynamics/PoseRTV.h>

View File

@ -56,4 +56,4 @@ for i=1:result.size()
end
axis([-0.6 4.8 -1 1])
axis equal
view(2)
view(2)

View File

@ -33,8 +33,8 @@ initialEstimate.insertPose(3, gtsamPose2(4.1, 0.1, 0.1));
%% Optimize using Levenberg-Marquardt optimization with an ordering from colamd
result = graph.optimize(initialEstimate,0);
marginals = graph.marginals(result);
marginals.marginalCovariance(i);
marginals.marginalCovariance(1);
%% Check first pose equality
pose_i = result.pose(1);
CHECK('pose_1.equals(gtsamPose2,1e-4)',pose_1.equals(gtsamPose2,1e-4));
pose_1 = result.pose(1);
CHECK('pose_1.equals(gtsamPose2,1e-4)',pose_1.equals(gtsamPose2,1e-4));

View File

@ -12,6 +12,7 @@
/**
* @file Argument.ccp
* @author Frank Dellaert
* @author Andrew Melim
**/
#include <iostream>
@ -53,14 +54,14 @@ void Argument::matlab_unwrap(FileWriter& file, const string& matlabName) const {
file.oss << "boost::shared_ptr<" << cppType << "> " << name << " = unwrap_shared_ptr< ";
else if (is_ref)
// A reference: emit an "unwrap_shared_ptr" call and de-reference the pointer
file.oss << cppType << "& " << name << " = *unwrap_shared_ptr< ";
file.oss << " " << cppType << "& " << name << " = *unwrap_shared_ptr< ";
else
// Not a pointer or a reference: emit an "unwrap" call
// unwrap is specified in matlab.h as a series of template specializations
// that know how to unpack the expected MATLAB object
// example: double tol = unwrap< double >(in[2]);
// example: Vector v = unwrap< Vector >(in[1]);
file.oss << cppType << " " << name << " = unwrap< ";
file.oss << " " << cppType << " " << name << " = unwrap< ";
file.oss << cppType << " >(" << matlabName;
if (is_ptr || is_ref) file.oss << ", \"" << matlabType << "\"";
@ -126,3 +127,4 @@ void ArgumentList::matlab_unwrap(FileWriter& file, int start) const {
}
/* ************************************************************************* */

View File

@ -13,6 +13,7 @@
* @file Argument.h
* @brief arguments to constructors and methods
* @author Frank Dellaert
* @author Andrew Melim
**/
#pragma once
@ -65,6 +66,7 @@ struct ArgumentList: public std::vector<Argument> {
* @param start initial index for input array, set to 1 for method
*/
void matlab_unwrap(FileWriter& file, int start = 0) const; // MATLAB to C++
};
} // \namespace wrap

View File

@ -10,8 +10,9 @@
* -------------------------------------------------------------------------- */
/**
* @file Class.ccp
* @file Class.cpp
* @author Frank Dellaert
* @author Andrew Melim
**/
#include <vector>
@ -22,6 +23,7 @@
#include "Class.h"
#include "utilities.h"
#include "Argument.h"
using namespace std;
using namespace wrap;
@ -43,13 +45,25 @@ void Class::matlab_proxy(const string& classFile) const {
file.oss << " methods" << endl;
// constructor
file.oss << " function obj = " << matlabName << "(varargin)" << endl;
BOOST_FOREACH(Constructor c, constructors)
c.matlab_proxy_fragment(file,matlabName);
file.oss << " if nargin ~= 13 && obj.self == 0, error('" << matlabName << " constructor failed'); end" << 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 << " delete_" << matlabName << "(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;
@ -61,18 +75,19 @@ void Class::matlab_proxy(const string& classFile) const {
}
/* ************************************************************************* */
//TODO: Consolidate into single file
void Class::matlab_constructors(const string& toolboxPath) const {
BOOST_FOREACH(Constructor c, constructors) {
c.matlab_mfile (toolboxPath, qualifiedName());
c.matlab_wrapper(toolboxPath, qualifiedName("::"), qualifiedName(), using_namespaces, includes);
/*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_deconstructor(const string& toolboxPath) const {
d.matlab_mfile (toolboxPath, qualifiedName());
d.matlab_wrapper(toolboxPath, qualifiedName("::"), qualifiedName(), using_namespaces, includes);
}
/* ************************************************************************* */
void Class::matlab_methods(const string& classPath) const {
string matlabName = qualifiedName(), cppName = qualifiedName("::");
@ -97,9 +112,7 @@ void Class::matlab_make_fragment(FileWriter& file,
const string& mexFlags) const {
string mex = "mex " + mexFlags + " ";
string matlabClassName = qualifiedName();
BOOST_FOREACH(Constructor c, constructors)
file.oss << mex << c.matlab_wrapper_name(matlabClassName) << ".cpp" << endl;
file.oss << mex << d.matlab_wrapper_name(matlabClassName) << ".cpp" << endl;
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;
@ -123,15 +136,12 @@ void Class::makefile_fragment(FileWriter& file) const {
//
// Point2: new_Point2_.$(MEXENDING) new_Point2_dd.$(MEXENDING) @Point2/x.$(MEXENDING) @Point2/y.$(MEXENDING) @Point2/dim.$(MEXENDING)
string matlabName = qualifiedName();
string matlabName = qualifiedName();
// collect names
vector<string> file_names;
BOOST_FOREACH(Constructor c, constructors) {
string file_base = c.matlab_wrapper_name(matlabName);
file_names.push_back(file_base);
}
file_names.push_back(d.matlab_wrapper_name(matlabName));
// collect names
vector<string> 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);
@ -142,7 +152,8 @@ void Class::makefile_fragment(FileWriter& file) const {
}
BOOST_FOREACH(const string& file_base, file_names) {
file.oss << file_base << ".$(MEXENDING): " << file_base << ".cpp" << endl;
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;
}

View File

@ -13,6 +13,7 @@
* @file Class.h
* @brief describe the C++ class that is being wrapped
* @author Frank Dellaert
* @author Andrew Melim
**/
#pragma once
@ -33,19 +34,17 @@ struct Class {
// Then the instance variables are set directly by the Module constructor
std::string name; ///< Class name
std::vector<Constructor> constructors; ///< Class constructors
std::vector<Method> methods; ///< Class methods
std::vector<StaticMethod> static_methods; ///< Static methods
std::vector<std::string> namespaces; ///< Stack of namespaces
std::vector<std::string> using_namespaces; ///< default namespaces
std::vector<std::string> includes; ///< header include overrides
Deconstructor d;
Constructor constructor; ///< Class constructors
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_deconstructor(const std::string& toolboxPath) const;
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,

View File

@ -12,10 +12,12 @@
/**
* @file Constructor.ccp
* @author Frank Dellaert
* @author Andrew Melim
**/
#include <iostream>
#include <fstream>
#include <algorithm>
#include <boost/foreach.hpp>
@ -25,14 +27,16 @@
using namespace std;
using namespace wrap;
/* ************************************************************************* */
string Constructor::matlab_wrapper_name(const string& className) const {
string str = "new_" + className + "_" + args.signature();
string str = "new_" + className + "_";
return str;
}
/* ************************************************************************* */
void Constructor::matlab_proxy_fragment(FileWriter& file, const string& className) const {
void Constructor::matlab_proxy_fragment(FileWriter& file,
const string& className, const int id, const ArgumentList args) const {
size_t nrArgs = args.size();
// check for number of arguments...
file.oss << " if (nargin == " << nrArgs;
@ -45,19 +49,17 @@ void Constructor::matlab_proxy_fragment(FileWriter& file, const string& classNam
first=false;
}
// emit code for calling constructor
file.oss << "), obj.self = " << matlab_wrapper_name(className) << "(";
file.oss << "), obj.self = " << matlab_wrapper_name(className) << "(" << "0," << id;
// emit constructor arguments
first = true;
for(size_t i=0;i<nrArgs;i++) {
if (!first) file.oss << ",";
file.oss << ",";
file.oss << "varargin{" << i+1 << "}";
first=false;
}
file.oss << "); end" << endl;
}
/* ************************************************************************* */
void Constructor::matlab_mfile(const string& toolboxPath, const string& qualifiedMatlabName) const {
void Constructor::matlab_mfile(const string& toolboxPath, const string& qualifiedMatlabName, const ArgumentList args) const {
string matlabName = matlab_wrapper_name(qualifiedMatlabName);
@ -80,7 +82,8 @@ void Constructor::matlab_mfile(const string& toolboxPath, const string& qualifie
void Constructor::matlab_wrapper(const string& toolboxPath,
const string& cppClassName,
const string& matlabClassName,
const vector<string>& using_namespaces, const vector<string>& includes) const {
const vector<string>& using_namespaces,
const vector<string>& includes) const {
string matlabName = matlab_wrapper_name(matlabClassName);
// open destination wrapperFile
@ -91,12 +94,66 @@ void Constructor::matlab_wrapper(const string& toolboxPath,
generateIncludes(file, name, includes);
generateUsingNamespace(file, using_namespaces);
//Typedef boost::shared_ptr
file.oss << "typedef boost::shared_ptr<" << cppClassName << "> Shared;" << endl;
file.oss << endl;
//Generate collector
file.oss << "static std::set<Shared*> collector;" << endl;
file.oss << endl;
//Generate the destructor function
file.oss << "struct Destruct" << endl;
file.oss << "{" << endl;
file.oss << " void operator() (Shared* p)" << endl;
file.oss << " {" << endl;
file.oss << " collector.erase(p);" << endl;
file.oss << " }" << endl;
file.oss << "};" << endl;
file.oss << endl;
//Generate cleanup function
file.oss << "void cleanup(void) {" << endl;
file.oss << " std::for_each( collector.begin(), collector.end(), Destruct() );" << endl;
file.oss << "}" << endl;
file.oss << "void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[])" << endl;
file.oss << "{" << endl;
file.oss << " checkArguments(\"" << matlabName << "\",nargout,nargin," << args.size() << ");" << endl;
args.matlab_unwrap(file); // unwrap arguments
file.oss << " " << cppClassName << "* self = new " << cppClassName << "(" << args.names() << ");" << endl; // need qualified name, delim: "::"
file.oss << " out[0] = wrap_constructed(self,\"" << matlabClassName << "\");" << endl; // need matlab qualified name
//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<int>(in[1]);" << endl;
int i = 0;
BOOST_FOREACH(ArgumentList al, args_list)
{
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;
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<Shared**> (mxGetPr(out[0])) = self;" << endl;
file.oss << " }" << endl;
file.oss << "}" << endl;
// close file

View File

@ -28,12 +28,12 @@ namespace wrap {
struct Constructor {
/// Constructor creates an empty class
Constructor(bool verbose = true) :
Constructor(bool verbose = false) :
verbose_(verbose) {
}
// Then the instance variables are set directly by the Module constructor
ArgumentList args;
std::vector<ArgumentList> args_list;
std::string name;
bool verbose_;
@ -48,11 +48,14 @@ 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;
void matlab_proxy_fragment(FileWriter& file,
const std::string& className, const int i,
const ArgumentList args) const;
/// m-file
void matlab_mfile(const std::string& toolboxPath,
const std::string& qualifiedMatlabName) const;
const std::string& qualifiedMatlabName,
const ArgumentList args) const;
/// cpp wrapper
void matlab_wrapper(const std::string& toolboxPath,
@ -60,7 +63,12 @@ struct Constructor {
const std::string& matlabClassName,
const std::vector<std::string>& using_namespaces,
const std::vector<std::string>& includes) const;
/// constructor function
void generate_construct(FileWriter& file, const std::string& cppClassName,
std::vector<ArgumentList>& args_list) const;
};
} // \namespace wrap
} // \namespace wrap

View File

@ -46,6 +46,10 @@ void FileWriter::emit(bool add_header, bool force_overwrite) const {
ofs << new_contents;
ofs.close();
if (verbose_) cerr << " ...complete" << endl;
// Add small message whenever writing a new file and not running in full verbose mode
if (!verbose_)
cout << "wrap: generating " << filename_ << endl;
} else {
if (verbose_) cerr << " ...no update" << endl;
}

View File

@ -61,6 +61,18 @@ void Method::matlab_wrapper(const string& classPath,
generateIncludes(file, className, includes);
generateUsingNamespace(file, using_namespaces);
if(returnVal.isPair)
{
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
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
@ -73,9 +85,9 @@ void Method::matlab_wrapper(const string& classPath,
// get class pointer
// example: shared_ptr<Test> = unwrap_shared_ptr< Test >(in[0], "Test");
file.oss << " boost::shared_ptr<" << cppClassName << "> self = unwrap_shared_ptr< " << cppClassName
<< " >(in[0],\"" << matlabClassName << "\");" << endl;
file.oss << " mxArray* mxh = mxGetProperty(in[0],0,\"self\");" << endl;
file.oss << " Shared* self = *reinterpret_cast<Shared**> (mxGetPr(mxh));" << endl;
file.oss << " Shared obj = *self;" << endl;
// unwrap arguments, see Argument.cpp
args.matlab_unwrap(file,1);
@ -84,7 +96,7 @@ void Method::matlab_wrapper(const string& classPath,
file.oss << " ";
if (returnVal.type1!="void")
file.oss << returnVal.return_type(true,ReturnValue::pair) << " result = ";
file.oss << "self->" << name << "(" << args.names() << ");\n";
file.oss << "obj->" << name << "(" << args.names() << ");\n";
// wrap result
// example: out[0]=wrap<bool>(result);

View File

@ -26,8 +26,10 @@
#include <boost/spirit/include/classic_clear_actor.hpp>
#include <boost/foreach.hpp>
#include <boost/filesystem.hpp>
#include <boost/lexical_cast.hpp>
#include <iostream>
#include <algorithm>
using namespace std;
using namespace wrap;
@ -52,8 +54,9 @@ Module::Module(const string& interfacePath,
ReturnValue retVal0, retVal;
Argument arg0, arg;
ArgumentList args0, args;
vector<string> arg_dup; ///keep track of duplicates
Constructor constructor0(enable_verbose), constructor(enable_verbose);
Deconstructor deconstructor0(enable_verbose), deconstructor(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);
@ -118,11 +121,12 @@ Module::Module(const string& interfacePath,
Rule constructor_p =
(className_p >> '(' >> argumentList_p >> ')' >> ';' >> !comments_p)
[assign_a(constructor.args,args)]
[assign_a(constructor.name,cls.name)]
[assign_a(args,args0)]
[push_back_a(cls.constructors, constructor)]
[assign_a(constructor,constructor0)];
[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("::");
@ -184,13 +188,16 @@ Module::Module(const string& interfacePath,
>> '{'
>> *(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)]
//[assign_a(deconstructor.name,cls.name)]
//[assign_a(cls.d, deconstructor)]
[push_back_a(classes,cls)]
[assign_a(deconstructor,deconstructor0)]
//[assign_a(deconstructor,deconstructor0)]
[assign_a(constructor, constructor0)]
[assign_a(cls,cls0)];
Rule namespace_def_p =
@ -280,7 +287,7 @@ void verifyReturnTypes(const vector<string>& validtypes, const vector<T>& vt) {
/* ************************************************************************* */
void Module::matlab_code(const string& mexCommand, const string& toolboxPath,
const string& mexExt, const string& mexFlags) const {
const string& mexExt, const string& headerPath,const string& mexFlags) const {
fs::create_directories(toolboxPath);
@ -301,6 +308,7 @@ void Module::matlab_code(const string& mexCommand, const string& toolboxPath,
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
@ -336,7 +344,7 @@ void Module::matlab_code(const string& mexCommand, const string& toolboxPath,
cls.matlab_proxy(classFile);
// verify all of the function arguments
verifyArguments<Constructor>(validTypes, cls.constructors);
//TODO:verifyArguments<ArgumentList>(validTypes, cls.constructor.args_list);
verifyArguments<StaticMethod>(validTypes, cls.static_methods);
verifyArguments<Method>(validTypes, cls.methods);
@ -350,7 +358,7 @@ void Module::matlab_code(const string& mexCommand, const string& toolboxPath,
cls.matlab_methods(classPath);
// create deconstructor
cls.matlab_deconstructor(toolboxPath);
//cls.matlab_deconstructor(toolboxPath);
// add lines to make m-file
makeModuleMfile.oss << "%% " << cls.qualifiedName() << endl;

View File

@ -44,6 +44,7 @@ struct Module {
const std::string& mexCommand,
const std::string& path,
const std::string& mexExt,
const std::string& headerPath,
const std::string& mexFlags) const;
};

View File

@ -3,6 +3,7 @@
*
* @date Dec 1, 2011
* @author Alex Cunningham
* @author Andrew Melim
*/
#include <boost/foreach.hpp>
@ -17,11 +18,11 @@ using namespace wrap;
string ReturnValue::return_type(bool add_ptr, pairing p) const {
if (p==pair && isPair) {
string str = "pair< " +
maybe_shared_ptr(add_ptr && isPtr1, qualifiedType1("::")) + ", " +
maybe_shared_ptr(add_ptr && isPtr2, qualifiedType2("::")) + " >";
maybe_shared_ptr(add_ptr && isPtr1, qualifiedType1("::"), type1) + ", " +
maybe_shared_ptr(add_ptr && isPtr2, qualifiedType2("::"), type2) + " >";
return str;
} else
return maybe_shared_ptr(add_ptr && isPtr1, (p==arg2)? qualifiedType2("::") : qualifiedType1("::"));
return maybe_shared_ptr(add_ptr && isPtr1, (p==arg2)? qualifiedType2("::") : qualifiedType1("::"), (p==arg2)? type2 : type1);
}
/* ************************************************************************* */
@ -44,31 +45,44 @@ string ReturnValue::qualifiedType2(const string& delim) const {
}
/* ************************************************************************* */
//TODO:Fix this
void ReturnValue::wrap_result(FileWriter& file) 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 << " out[0] = wrap_shared_ptr(result.first,\"" << matlabType1 << "\");\n";
else if (category1 == ReturnValue::CLASS) // if we are going to make one
file.oss << " out[0] = wrap_shared_ptr(boost::make_shared< " << cppType1 << " >(result.first),\"" << matlabType1 << "\");\n";
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";
// second return value in pair
if (isPtr2) // if we already have a pointer
file.oss << " out[1] = wrap_shared_ptr(result.second,\"" << matlabType2 << "\");\n";
else if (category2 == ReturnValue::CLASS) // if we are going to make one
file.oss << " out[1] = wrap_shared_ptr(boost::make_shared< " << cppType2 << " >(result.second),\"" << matlabType2 << "\");\n";
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 << " out[0] = wrap_shared_ptr(result,\"" << matlabType1 << "\");\n";
else if (category1 == ReturnValue::CLASS)
file.oss << " out[0] = wrap_shared_ptr(boost::make_shared< " << cppType1 << " >(result),\"" << matlabType1 << "\");\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";
}
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";
}

View File

@ -10,8 +10,9 @@
* -------------------------------------------------------------------------- */
/**
* @file Method.ccp
* @file StaticMethod.ccp
* @author Frank Dellaert
* @author Andrew Melim
**/
#include <iostream>
@ -62,6 +63,15 @@ void StaticMethod::matlab_wrapper(const string& toolboxPath, const string& class
generateIncludes(file, className, includes);
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;
}
else
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

View File

@ -41,6 +41,8 @@ extern "C" {
#include <list>
#include <string>
#include <sstream>
#include <typeinfo>
#include <set>
using namespace std;
using namespace boost; // not usual, but for conciseness of generated code
@ -311,113 +313,6 @@ gtsam::Matrix unwrap< gtsam::Matrix >(const mxArray* array) {
return A;
}
//*****************************************************************************
// Shared Pointer Handle
// inspired by mexhandle, but using shared_ptr
//*****************************************************************************
template<typename T>
class ObjectHandle {
private:
ObjectHandle* signature; // use 'this' as a unique object signature
const std::type_info* type; // type checking information
boost::shared_ptr<T> t; // object pointer
public:
// Constructor for free-store allocated objects.
// Creates shared pointer, will delete if is last one to hold pointer
ObjectHandle(T* ptr) :
type(&typeid(T)), t(ptr) {
signature = this;
}
// Constructor for shared pointers
// Creates shared pointer, will delete if is last one to hold pointer
ObjectHandle(boost::shared_ptr<T> shared_ptr) :
/*type(&typeid(T)),*/ t(shared_ptr) {
signature = this;
}
~ObjectHandle() {
// object is in shared_ptr, will be automatically deleted
signature = 0; // destroy signature
// std::cout << "ObjectHandle destructor" << std::endl;
}
// Get the actual object contained by handle
boost::shared_ptr<T> get_object() const {
return t;
}
// Print the mexhandle for debugging
void print(const char* str) {
mexPrintf("mexhandle %s:\n", str);
mexPrintf(" signature = %d:\n", signature);
mexPrintf(" pointer = %d:\n", t.get());
}
// Convert ObjectHandle<T> to a mxArray handle (to pass back from mex-function).
// Create a numeric array as handle for an ObjectHandle.
// We ASSUME we can store object pointer in the mxUINT32 element of mxArray.
mxArray* to_mex_handle() {
mxArray* handle = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL);
*reinterpret_cast<ObjectHandle<T>**> (mxGetPr(handle)) = this;
return handle;
}
string type_name() const {
return type->name();
}
// Convert mxArray (passed to mex-function) to an ObjectHandle<T>.
// Import a handle from MatLab as a mxArray of UINT32. Check that
// it is actually a pointer to an ObjectHandle<T>.
static ObjectHandle* from_mex_handle(const mxArray* handle) {
if (mxGetClassID(handle) != mxUINT32OR64_CLASS || mxIsComplex(handle)
|| mxGetM(handle) != 1 || mxGetN(handle) != 1) error(
"Parameter is not an ObjectHandle type.");
// We *assume* we can store ObjectHandle<T> pointer in the mxUINT32 of handle
ObjectHandle* obj = *reinterpret_cast<ObjectHandle**> (mxGetPr(handle));
if (!obj) // gross check to see we don't have an invalid pointer
error("Parameter is NULL. It does not represent an ObjectHandle object.");
// TODO: change this for max-min check for pointer values
if (obj->signature != obj) // check memory has correct signature
error("Parameter does not represent an ObjectHandle object.");
/*
if (*(obj->type) != typeid(T)) { // check type
mexPrintf("Given: <%s>, Required: <%s>.\n", obj->type_name(), typeid(T).name());
error("Given ObjectHandle does not represent the correct type.");
}
*/
return obj;
}
};
//*****************************************************************************
// wrapping C++ objects in a MATLAB proxy class
//*****************************************************************************
/*
For every C++ class Class, a matlab proxy class @Class/Class.m object
is created. Its constructor will check which of the C++ constructors
needs to be called, based on nr of arguments. It then calls the
corresponding mex function new_Class_signature, which will create a
C++ object using new, and pass the pointer to wrap_constructed
(below). This creates a mexhandle and returns it to the proxy class
constructor, which assigns it to self. Matlab owns this handle now.
*/
template <typename Class>
mxArray* wrap_constructed(Class* pointer, const char *classname) {
ObjectHandle<Class>* handle = new ObjectHandle<Class>(pointer);
return handle->to_mex_handle();
}
/*
[create_object] creates a MATLAB proxy class object with a mexhandle
in the self property. Matlab does not allow the creation of matlab
@ -435,138 +330,49 @@ mxArray* create_object(const char *classname, mxArray* h) {
return result;
}
/*
* Similar to create object, this also collects the shared_ptr in addition
* to creating the dummy object. Mainly used for static constructor methods
* which don't have direct access to the function.
*/
mxArray* create_collect_object(const char *classname, mxArray* h){
mxArray *result;
//First arg is a flag to collect
mxArray* dummy[14] = {h,h,h,h,h, h,h,h,h,h, h,h,h,h};
mexCallMATLAB(1,&result,14,dummy,classname);
mxSetProperty(result, 0, "self", h);
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 <typename Class>
mxArray* wrap_shared_ptr(boost::shared_ptr< Class > shared_ptr, const char *classname) {
ObjectHandle<Class>* handle = new ObjectHandle<Class>(shared_ptr);
return create_object(classname,handle->to_mex_handle());
mxArray* wrap_shared_ptr(boost::shared_ptr< Class >* shared_ptr, const char *classname) {
mxArray* mxh = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL);
*reinterpret_cast<boost::shared_ptr<Class>**> (mxGetPr(mxh)) = shared_ptr;
//return mxh;
return create_object(classname, mxh);
}
//*****************************************************************************
// unwrapping a MATLAB proxy class to a C++ object reference
//*****************************************************************************
template <typename Class>
mxArray* wrap_collect_shared_ptr(boost::shared_ptr< Class >* shared_ptr, const char *classname) {
mxArray* mxh = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL);
*reinterpret_cast<boost::shared_ptr<Class>**> (mxGetPr(mxh)) = shared_ptr;
//return mxh;
return create_collect_object(classname, mxh);
}
/*
Besides the basis types, the only other argument type allowed is a
shared pointer to a C++ object. In this case, matlab needs to pass a
proxy class object to the mex function. [unwrap_shared_ptr] extracts
the ObjectHandle from the self property, and returns a shared pointer
to the object.
*/
template <typename Class>
boost::shared_ptr<Class> unwrap_shared_ptr(const mxArray* obj, const string& className) {
#ifndef UNSAFE_WRAP
// Useful code to check argument type
// Problem, does not support inheritance
bool isClass = mxIsClass(obj, className.c_str());
if (!isClass) {
mexPrintf("Expected %s, got %s\n", className.c_str(), mxGetClassName(obj));
error("Argument has wrong type.");
}
#endif
mxArray* mxh = mxGetProperty(obj,0,"self");
if (mxh==NULL) error("unwrap_reference: invalid wrap object");
ObjectHandle<Class>* handle = ObjectHandle<Class>::from_mex_handle(mxh);
return handle->get_object();
if (mxGetClassID(mxh) != mxUINT32OR64_CLASS || mxIsComplex(mxh)
|| mxGetM(mxh) != 1 || mxGetN(mxh) != 1) error(
"Parameter is not an Shared type.");
boost::shared_ptr<Class>* spp = *reinterpret_cast<boost::shared_ptr<Class>**> (mxGetPr(mxh));
return *spp;
}
/*
* Specialized template for noise model. Checking their derived types properly
*/
// Isotropic
template <>
boost::shared_ptr<Isotropic> unwrap_shared_ptr(const mxArray* obj, const string& className) {
#ifndef UNSAFE_WRAP
bool isIsotropic = mxIsClass(obj, "gtsamnoiseModelIsotropic");
bool isUnit = mxIsClass(obj, "gtsamnoiseModelUnit");
if (!isIsotropic && !isUnit) {
mexPrintf("Expected gtsamnoiseModelIsotropic or derived classes, got %s\n", mxGetClassName(obj));
error("Argument has wrong type.");
}
#endif
mxArray* mxh = mxGetProperty(obj,0,"self");
if (mxh==NULL) error("unwrap_reference: invalid wrap object");
ObjectHandle<Isotropic>* handle = ObjectHandle<Isotropic>::from_mex_handle(mxh);
return handle->get_object();
}
// Diagonal
template <>
boost::shared_ptr<Diagonal> unwrap_shared_ptr(const mxArray* obj, const string& className) {
#ifndef UNSAFE_WRAP
bool isDiagonal = mxIsClass(obj, "gtsamnoiseModelDiagonal");
bool isIsotropic = mxIsClass(obj, "gtsamnoiseModelIsotropic");
bool isUnit = mxIsClass(obj, "gtsamnoiseModelUnit");
if (!isDiagonal && !isIsotropic && !isUnit ) {
mexPrintf("Expected gtsamnoiseModelDiagonal or derived classes, got %s\n", mxGetClassName(obj));
error("Argument has wrong type.");
}
#endif
mxArray* mxh = mxGetProperty(obj,0,"self");
if (mxh==NULL) error("unwrap_reference: invalid wrap object");
ObjectHandle<Isotropic>* handle = ObjectHandle<Isotropic>::from_mex_handle(mxh);
return handle->get_object();
}
// Gaussian
template <>
boost::shared_ptr<Gaussian> unwrap_shared_ptr(const mxArray* obj, const string& className) {
#ifndef UNSAFE_WRAP
bool isGaussian = mxIsClass(obj, "gtsamnoiseModelGaussian");
bool isDiagonal = mxIsClass(obj, "gtsamnoiseModelDiagonal");
bool isIsotropic = mxIsClass(obj, "gtsamnoiseModelIsotropic");
bool isUnit = mxIsClass(obj, "gtsamnoiseModelUnit");
if (!isGaussian && !isDiagonal && !isIsotropic && !isUnit) {
mexPrintf("Expected gtsamnoiseModelGaussian or derived classes, got %s\n", mxGetClassName(obj));
error("Argument has wrong type.");
}
#endif
mxArray* mxh = mxGetProperty(obj,0,"self");
if (mxh==NULL) error("unwrap_reference: invalid wrap object");
ObjectHandle<Isotropic>* handle = ObjectHandle<Isotropic>::from_mex_handle(mxh);
return handle->get_object();
}
// Base
template <>
boost::shared_ptr<Base> unwrap_shared_ptr(const mxArray* obj, const string& className) {
#ifndef UNSAFE_WRAP
bool isBase = mxIsClass(obj, "gtsamnoiseModelBase");
bool isGaussian = mxIsClass(obj, "gtsamnoiseModelGaussian");
bool isDiagonal = mxIsClass(obj, "gtsamnoiseModelDiagonal");
bool isIsotropic = mxIsClass(obj, "gtsamnoiseModelIsotropic");
bool isUnit = mxIsClass(obj, "gtsamnoiseModelUnit");
if (!isBase && !isGaussian && !isDiagonal && !isIsotropic && !isUnit) {
mexPrintf("Expected gtsamnoiseModelBase or derived classes, got %s\n", mxGetClassName(obj));
error("Argument has wrong type.");
}
#endif
mxArray* mxh = mxGetProperty(obj,0,"self");
if (mxh==NULL) error("unwrap_reference: invalid wrap object");
ObjectHandle<Isotropic>* handle = ObjectHandle<Isotropic>::from_mex_handle(mxh);
return handle->get_object();
}
//end specialized templates
template <typename Class>
void delete_shared_ptr(const mxArray* obj, const string& className) {
//Why is this here?
#ifndef UNSAFE_WRAP
bool isClass = true;//mxIsClass(obj, className.c_str());
if (!isClass) {
mexPrintf("Expected %s, got %s\n", className.c_str(), mxGetClassName(obj));
error("Argument has wrong type.");
}
#endif
mxArray* mxh = mxGetProperty(obj,0,"self");
if (mxh==NULL) error("unwrap_reference: invalid wrap object");
ObjectHandle<Class>* handle = ObjectHandle<Class>::from_mex_handle(mxh);
delete handle;
}
//*****************************************************************************

View File

@ -5,12 +5,16 @@ classdef Point2 < handle
end
methods
function obj = Point2(varargin)
if (nargin == 0), obj.self = new_Point2_(); end
if (nargin == 2 && isa(varargin{1},'double') && isa(varargin{2},'double')), obj.self = new_Point2_dd(varargin{1},varargin{2}); end
if nargin ~= 13 && obj.self == 0, error('Point2 constructor failed'); end
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)
delete_Point2(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

View File

@ -1,10 +1,14 @@
// automatically generated by wrap
#include <wrap/matlab.h>
#include <set>
#include <Point2.h>
typedef boost::shared_ptr<Point2> Shared;
void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
checkArguments("argChar",nargout,nargin-1,1);
boost::shared_ptr<Point2> self = unwrap_shared_ptr< Point2 >(in[0],"Point2");
char a = unwrap< char >(in[1]);
self->argChar(a);
mxArray* mxh = mxGetProperty(in[0],0,"self");
Shared* self = *reinterpret_cast<Shared**> (mxGetPr(mxh));
Shared obj = *self;
char a = unwrap< char >(in[1]);
obj->argChar(a);
}

View File

@ -1,5 +1,4 @@
% automatically generated by wrap
% result = obj.argChar(a)
function result = argChar(obj,a)
% usage: obj.argChar(a)
error('need to compile argChar.cpp');
end

View File

@ -1,10 +1,14 @@
// automatically generated by wrap
#include <wrap/matlab.h>
#include <set>
#include <Point2.h>
typedef boost::shared_ptr<Point2> Shared;
void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
checkArguments("argUChar",nargout,nargin-1,1);
boost::shared_ptr<Point2> self = unwrap_shared_ptr< Point2 >(in[0],"Point2");
unsigned char a = unwrap< unsigned char >(in[1]);
self->argUChar(a);
mxArray* mxh = mxGetProperty(in[0],0,"self");
Shared* self = *reinterpret_cast<Shared**> (mxGetPr(mxh));
Shared obj = *self;
unsigned char a = unwrap< unsigned char >(in[1]);
obj->argUChar(a);
}

View File

@ -1,5 +1,4 @@
% automatically generated by wrap
% result = obj.argUChar(a)
function result = argUChar(obj,a)
% usage: obj.argUChar(a)
error('need to compile argUChar.cpp');
end

View File

@ -1,10 +1,14 @@
// automatically generated by wrap
#include <wrap/matlab.h>
#include <set>
#include <Point2.h>
typedef boost::shared_ptr<Point2> Shared;
void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
checkArguments("dim",nargout,nargin-1,0);
boost::shared_ptr<Point2> self = unwrap_shared_ptr< Point2 >(in[0],"Point2");
int result = self->dim();
mxArray* mxh = mxGetProperty(in[0],0,"self");
Shared* self = *reinterpret_cast<Shared**> (mxGetPr(mxh));
Shared obj = *self;
int result = obj->dim();
out[0] = wrap< int >(result);
}

View File

@ -1,5 +1,4 @@
% automatically generated by wrap
% result = obj.dim()
function result = dim(obj)
% usage: obj.dim()
error('need to compile dim.cpp');
end

View File

@ -1,10 +1,14 @@
// automatically generated by wrap
#include <wrap/matlab.h>
#include <set>
#include <Point2.h>
typedef boost::shared_ptr<Point2> Shared;
void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
checkArguments("returnChar",nargout,nargin-1,0);
boost::shared_ptr<Point2> self = unwrap_shared_ptr< Point2 >(in[0],"Point2");
char result = self->returnChar();
mxArray* mxh = mxGetProperty(in[0],0,"self");
Shared* self = *reinterpret_cast<Shared**> (mxGetPr(mxh));
Shared obj = *self;
char result = obj->returnChar();
out[0] = wrap< char >(result);
}

View File

@ -1,5 +1,4 @@
% automatically generated by wrap
% result = obj.returnChar()
function result = returnChar(obj)
% usage: obj.returnChar()
error('need to compile returnChar.cpp');
end

View File

@ -1,10 +1,16 @@
// automatically generated by wrap
#include <wrap/matlab.h>
#include <set>
#include <Point2.h>
typedef boost::shared_ptr<VectorNotEigen> SharedVectorNotEigen;
typedef boost::shared_ptr<Point2> Shared;
void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
checkArguments("vectorConfusion",nargout,nargin-1,0);
boost::shared_ptr<Point2> self = unwrap_shared_ptr< Point2 >(in[0],"Point2");
VectorNotEigen result = self->vectorConfusion();
out[0] = wrap_shared_ptr(boost::make_shared< VectorNotEigen >(result),"VectorNotEigen");
mxArray* mxh = mxGetProperty(in[0],0,"self");
Shared* self = *reinterpret_cast<Shared**> (mxGetPr(mxh));
Shared obj = *self;
VectorNotEigen result = obj->vectorConfusion();
SharedVectorNotEigen* ret = new SharedVectorNotEigen(new VectorNotEigen(result));
out[0] = wrap_collect_shared_ptr(ret,"VectorNotEigen");
}

View File

@ -1,5 +1,4 @@
% automatically generated by wrap
% result = obj.vectorConfusion()
function result = vectorConfusion(obj)
% usage: obj.vectorConfusion()
error('need to compile vectorConfusion.cpp');
end

View File

@ -1,10 +1,14 @@
// automatically generated by wrap
#include <wrap/matlab.h>
#include <set>
#include <Point2.h>
typedef boost::shared_ptr<Point2> Shared;
void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
checkArguments("x",nargout,nargin-1,0);
boost::shared_ptr<Point2> self = unwrap_shared_ptr< Point2 >(in[0],"Point2");
double result = self->x();
mxArray* mxh = mxGetProperty(in[0],0,"self");
Shared* self = *reinterpret_cast<Shared**> (mxGetPr(mxh));
Shared obj = *self;
double result = obj->x();
out[0] = wrap< double >(result);
}

View File

@ -1,5 +1,4 @@
% automatically generated by wrap
% result = obj.x()
function result = x(obj)
% usage: obj.x()
error('need to compile x.cpp');
end

View File

@ -1,10 +1,14 @@
// automatically generated by wrap
#include <wrap/matlab.h>
#include <set>
#include <Point2.h>
typedef boost::shared_ptr<Point2> Shared;
void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
checkArguments("y",nargout,nargin-1,0);
boost::shared_ptr<Point2> self = unwrap_shared_ptr< Point2 >(in[0],"Point2");
double result = self->y();
mxArray* mxh = mxGetProperty(in[0],0,"self");
Shared* self = *reinterpret_cast<Shared**> (mxGetPr(mxh));
Shared obj = *self;
double result = obj->y();
out[0] = wrap< double >(result);
}

View File

@ -1,5 +1,4 @@
% automatically generated by wrap
% result = obj.y()
function result = y(obj)
% usage: obj.y()
error('need to compile y.cpp');
end

View File

@ -5,11 +5,15 @@ classdef Point3 < handle
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_ddd(varargin{1},varargin{2},varargin{3}); end
if nargin ~= 13 && obj.self == 0, error('Point3 constructor failed'); end
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)
delete_Point3(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

View File

@ -1,11 +1,15 @@
// automatically generated by wrap
#include <wrap/matlab.h>
#include <set>
#include <Point3.h>
using namespace geometry;
typedef boost::shared_ptr<Point3> Shared;
void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
checkArguments("norm",nargout,nargin-1,0);
boost::shared_ptr<Point3> self = unwrap_shared_ptr< Point3 >(in[0],"Point3");
double result = self->norm();
mxArray* mxh = mxGetProperty(in[0],0,"self");
Shared* self = *reinterpret_cast<Shared**> (mxGetPr(mxh));
Shared obj = *self;
double result = obj->norm();
out[0] = wrap< double >(result);
}

View File

@ -5,12 +5,16 @@ classdef Test < handle
end
methods
function obj = Test(varargin)
if (nargin == 0), obj.self = new_Test_(); end
if (nargin == 2 && isa(varargin{1},'double') && isa(varargin{2},'double')), obj.self = new_Test_dM(varargin{1},varargin{2}); end
if nargin ~= 13 && obj.self == 0, error('Test constructor failed'); end
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)
delete_Test(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

View File

@ -1,11 +1,15 @@
// automatically generated by wrap
#include <wrap/matlab.h>
#include <set>
#include <folder/path/to/Test.h>
using namespace geometry;
typedef boost::shared_ptr<Test> Shared;
void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
checkArguments("arg_EigenConstRef",nargout,nargin-1,1);
boost::shared_ptr<Test> self = unwrap_shared_ptr< Test >(in[0],"Test");
Matrix& value = *unwrap_shared_ptr< Matrix >(in[1], "Matrix");
self->arg_EigenConstRef(value);
mxArray* mxh = mxGetProperty(in[0],0,"self");
Shared* self = *reinterpret_cast<Shared**> (mxGetPr(mxh));
Shared obj = *self;
Matrix& value = *unwrap_shared_ptr< Matrix >(in[1], "Matrix");
obj->arg_EigenConstRef(value);
}

View File

@ -1,5 +1,4 @@
% automatically generated by wrap
% result = obj.arg_EigenConstRef(value)
function result = arg_EigenConstRef(obj,value)
% usage: obj.arg_EigenConstRef(value)
error('need to compile arg_EigenConstRef.cpp');
end

View File

@ -1,12 +1,20 @@
// automatically generated by wrap
#include <wrap/matlab.h>
#include <set>
#include <folder/path/to/Test.h>
using namespace geometry;
typedef boost::shared_ptr<Test> SharedTest;
typedef boost::shared_ptr<Test> SharedTest;
typedef boost::shared_ptr<Test> Shared;
void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
checkArguments("create_MixedPtrs",nargout,nargin-1,0);
boost::shared_ptr<Test> self = unwrap_shared_ptr< Test >(in[0],"Test");
pair< Test, boost::shared_ptr<Test> > result = self->create_MixedPtrs();
out[0] = wrap_shared_ptr(boost::make_shared< Test >(result.first),"Test");
out[1] = wrap_shared_ptr(result.second,"Test");
mxArray* mxh = mxGetProperty(in[0],0,"self");
Shared* self = *reinterpret_cast<Shared**> (mxGetPr(mxh));
Shared obj = *self;
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");
}

View File

@ -1,5 +1,4 @@
% automatically generated by wrap
% [first,second] = obj.create_MixedPtrs()
function [first,second] = create_MixedPtrs(obj)
% usage: obj.create_MixedPtrs()
error('need to compile create_MixedPtrs.cpp');
end

View File

@ -1,12 +1,20 @@
// automatically generated by wrap
#include <wrap/matlab.h>
#include <set>
#include <folder/path/to/Test.h>
using namespace geometry;
typedef boost::shared_ptr<Test> SharedTest;
typedef boost::shared_ptr<Test> SharedTest;
typedef boost::shared_ptr<Test> Shared;
void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
checkArguments("create_ptrs",nargout,nargin-1,0);
boost::shared_ptr<Test> self = unwrap_shared_ptr< Test >(in[0],"Test");
pair< boost::shared_ptr<Test>, boost::shared_ptr<Test> > result = self->create_ptrs();
out[0] = wrap_shared_ptr(result.first,"Test");
out[1] = wrap_shared_ptr(result.second,"Test");
mxArray* mxh = mxGetProperty(in[0],0,"self");
Shared* self = *reinterpret_cast<Shared**> (mxGetPr(mxh));
Shared obj = *self;
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");
}

View File

@ -1,5 +1,4 @@
% automatically generated by wrap
% [first,second] = obj.create_ptrs()
function [first,second] = create_ptrs(obj)
% usage: obj.create_ptrs()
error('need to compile create_ptrs.cpp');
end

View File

@ -1,10 +1,14 @@
// automatically generated by wrap
#include <wrap/matlab.h>
#include <set>
#include <folder/path/to/Test.h>
using namespace geometry;
typedef boost::shared_ptr<Test> Shared;
void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
checkArguments("print",nargout,nargin-1,0);
boost::shared_ptr<Test> self = unwrap_shared_ptr< Test >(in[0],"Test");
self->print();
mxArray* mxh = mxGetProperty(in[0],0,"self");
Shared* self = *reinterpret_cast<Shared**> (mxGetPr(mxh));
Shared obj = *self;
obj->print();
}

View File

@ -1,12 +1,18 @@
// automatically generated by wrap
#include <wrap/matlab.h>
#include <set>
#include <folder/path/to/Test.h>
using namespace geometry;
typedef boost::shared_ptr<Point2> SharedPoint2;
typedef boost::shared_ptr<Test> Shared;
void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
checkArguments("return_Point2Ptr",nargout,nargin-1,1);
boost::shared_ptr<Test> self = unwrap_shared_ptr< Test >(in[0],"Test");
bool value = unwrap< bool >(in[1]);
boost::shared_ptr<Point2> result = self->return_Point2Ptr(value);
out[0] = wrap_shared_ptr(result,"Point2");
mxArray* mxh = mxGetProperty(in[0],0,"self");
Shared* self = *reinterpret_cast<Shared**> (mxGetPr(mxh));
Shared obj = *self;
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");
}

View File

@ -1,5 +1,4 @@
% automatically generated by wrap
% result = obj.return_Point2Ptr(value)
function result = return_Point2Ptr(obj,value)
% usage: obj.return_Point2Ptr(value)
error('need to compile return_Point2Ptr.cpp');
end

View File

@ -1,12 +1,18 @@
// automatically generated by wrap
#include <wrap/matlab.h>
#include <set>
#include <folder/path/to/Test.h>
using namespace geometry;
typedef boost::shared_ptr<Test> SharedTest;
typedef boost::shared_ptr<Test> Shared;
void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
checkArguments("return_Test",nargout,nargin-1,1);
boost::shared_ptr<Test> self = unwrap_shared_ptr< Test >(in[0],"Test");
mxArray* mxh = mxGetProperty(in[0],0,"self");
Shared* self = *reinterpret_cast<Shared**> (mxGetPr(mxh));
Shared obj = *self;
boost::shared_ptr<Test> value = unwrap_shared_ptr< Test >(in[1], "Test");
Test result = self->return_Test(value);
out[0] = wrap_shared_ptr(boost::make_shared< Test >(result),"Test");
Test result = obj->return_Test(value);
SharedTest* ret = new SharedTest(new Test(result));
out[0] = wrap_collect_shared_ptr(ret,"Test");
}

View File

@ -1,5 +1,4 @@
% automatically generated by wrap
% result = obj.return_Test(value)
function result = return_Test(obj,value)
% usage: obj.return_Test(value)
error('need to compile return_Test.cpp');
end

View File

@ -1,12 +1,18 @@
// automatically generated by wrap
#include <wrap/matlab.h>
#include <set>
#include <folder/path/to/Test.h>
using namespace geometry;
typedef boost::shared_ptr<Test> SharedTest;
typedef boost::shared_ptr<Test> Shared;
void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
checkArguments("return_TestPtr",nargout,nargin-1,1);
boost::shared_ptr<Test> self = unwrap_shared_ptr< Test >(in[0],"Test");
mxArray* mxh = mxGetProperty(in[0],0,"self");
Shared* self = *reinterpret_cast<Shared**> (mxGetPr(mxh));
Shared obj = *self;
boost::shared_ptr<Test> value = unwrap_shared_ptr< Test >(in[1], "Test");
boost::shared_ptr<Test> result = self->return_TestPtr(value);
out[0] = wrap_shared_ptr(result,"Test");
SharedTest result = obj->return_TestPtr(value);
SharedTest* ret = new SharedTest(result);
out[0] = wrap_collect_shared_ptr(ret,"Test");
}

View File

@ -1,5 +1,4 @@
% automatically generated by wrap
% result = obj.return_TestPtr(value)
function result = return_TestPtr(obj,value)
% usage: obj.return_TestPtr(value)
error('need to compile return_TestPtr.cpp');
end

View File

@ -1,12 +1,16 @@
// automatically generated by wrap
#include <wrap/matlab.h>
#include <set>
#include <folder/path/to/Test.h>
using namespace geometry;
typedef boost::shared_ptr<Test> Shared;
void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
checkArguments("return_bool",nargout,nargin-1,1);
boost::shared_ptr<Test> self = unwrap_shared_ptr< Test >(in[0],"Test");
bool value = unwrap< bool >(in[1]);
bool result = self->return_bool(value);
mxArray* mxh = mxGetProperty(in[0],0,"self");
Shared* self = *reinterpret_cast<Shared**> (mxGetPr(mxh));
Shared obj = *self;
bool value = unwrap< bool >(in[1]);
bool result = obj->return_bool(value);
out[0] = wrap< bool >(result);
}

View File

@ -1,5 +1,4 @@
% automatically generated by wrap
% result = obj.return_bool(value)
function result = return_bool(obj,value)
% usage: obj.return_bool(value)
error('need to compile return_bool.cpp');
end

View File

@ -1,12 +1,16 @@
// automatically generated by wrap
#include <wrap/matlab.h>
#include <set>
#include <folder/path/to/Test.h>
using namespace geometry;
typedef boost::shared_ptr<Test> Shared;
void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
checkArguments("return_double",nargout,nargin-1,1);
boost::shared_ptr<Test> self = unwrap_shared_ptr< Test >(in[0],"Test");
double value = unwrap< double >(in[1]);
double result = self->return_double(value);
mxArray* mxh = mxGetProperty(in[0],0,"self");
Shared* self = *reinterpret_cast<Shared**> (mxGetPr(mxh));
Shared obj = *self;
double value = unwrap< double >(in[1]);
double result = obj->return_double(value);
out[0] = wrap< double >(result);
}

View File

@ -1,5 +1,4 @@
% automatically generated by wrap
% result = obj.return_double(value)
function result = return_double(obj,value)
% usage: obj.return_double(value)
error('need to compile return_double.cpp');
end

View File

@ -1,12 +1,16 @@
// automatically generated by wrap
#include <wrap/matlab.h>
#include <set>
#include <folder/path/to/Test.h>
using namespace geometry;
typedef boost::shared_ptr<Test> Shared;
void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
checkArguments("return_field",nargout,nargin-1,1);
boost::shared_ptr<Test> self = unwrap_shared_ptr< Test >(in[0],"Test");
Test& t = *unwrap_shared_ptr< Test >(in[1], "Test");
bool result = self->return_field(t);
mxArray* mxh = mxGetProperty(in[0],0,"self");
Shared* self = *reinterpret_cast<Shared**> (mxGetPr(mxh));
Shared obj = *self;
Test& t = *unwrap_shared_ptr< Test >(in[1], "Test");
bool result = obj->return_field(t);
out[0] = wrap< bool >(result);
}

View File

@ -1,5 +1,4 @@
% automatically generated by wrap
% result = obj.return_field(t)
function result = return_field(obj,t)
% usage: obj.return_field(t)
error('need to compile return_field.cpp');
end

View File

@ -1,12 +1,16 @@
// automatically generated by wrap
#include <wrap/matlab.h>
#include <set>
#include <folder/path/to/Test.h>
using namespace geometry;
typedef boost::shared_ptr<Test> Shared;
void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
checkArguments("return_int",nargout,nargin-1,1);
boost::shared_ptr<Test> self = unwrap_shared_ptr< Test >(in[0],"Test");
int value = unwrap< int >(in[1]);
int result = self->return_int(value);
mxArray* mxh = mxGetProperty(in[0],0,"self");
Shared* self = *reinterpret_cast<Shared**> (mxGetPr(mxh));
Shared obj = *self;
int value = unwrap< int >(in[1]);
int result = obj->return_int(value);
out[0] = wrap< int >(result);
}

View File

@ -1,5 +1,4 @@
% automatically generated by wrap
% result = obj.return_int(value)
function result = return_int(obj,value)
% usage: obj.return_int(value)
error('need to compile return_int.cpp');
end

View File

@ -1,12 +1,16 @@
// automatically generated by wrap
#include <wrap/matlab.h>
#include <set>
#include <folder/path/to/Test.h>
using namespace geometry;
typedef boost::shared_ptr<Test> Shared;
void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
checkArguments("return_matrix1",nargout,nargin-1,1);
boost::shared_ptr<Test> self = unwrap_shared_ptr< Test >(in[0],"Test");
Matrix value = unwrap< Matrix >(in[1]);
Matrix result = self->return_matrix1(value);
mxArray* mxh = mxGetProperty(in[0],0,"self");
Shared* self = *reinterpret_cast<Shared**> (mxGetPr(mxh));
Shared obj = *self;
Matrix value = unwrap< Matrix >(in[1]);
Matrix result = obj->return_matrix1(value);
out[0] = wrap< Matrix >(result);
}

View File

@ -1,5 +1,4 @@
% automatically generated by wrap
% result = obj.return_matrix1(value)
function result = return_matrix1(obj,value)
% usage: obj.return_matrix1(value)
error('need to compile return_matrix1.cpp');
end

View File

@ -1,12 +1,16 @@
// automatically generated by wrap
#include <wrap/matlab.h>
#include <set>
#include <folder/path/to/Test.h>
using namespace geometry;
typedef boost::shared_ptr<Test> Shared;
void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
checkArguments("return_matrix2",nargout,nargin-1,1);
boost::shared_ptr<Test> self = unwrap_shared_ptr< Test >(in[0],"Test");
Matrix value = unwrap< Matrix >(in[1]);
Matrix result = self->return_matrix2(value);
mxArray* mxh = mxGetProperty(in[0],0,"self");
Shared* self = *reinterpret_cast<Shared**> (mxGetPr(mxh));
Shared obj = *self;
Matrix value = unwrap< Matrix >(in[1]);
Matrix result = obj->return_matrix2(value);
out[0] = wrap< Matrix >(result);
}

View File

@ -1,5 +1,4 @@
% automatically generated by wrap
% result = obj.return_matrix2(value)
function result = return_matrix2(obj,value)
% usage: obj.return_matrix2(value)
error('need to compile return_matrix2.cpp');
end

View File

@ -1,14 +1,18 @@
// automatically generated by wrap
#include <wrap/matlab.h>
#include <set>
#include <folder/path/to/Test.h>
using namespace geometry;
typedef boost::shared_ptr<Test> Shared;
void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
checkArguments("return_pair",nargout,nargin-1,2);
boost::shared_ptr<Test> self = unwrap_shared_ptr< Test >(in[0],"Test");
Vector v = unwrap< Vector >(in[1]);
Matrix A = unwrap< Matrix >(in[2]);
pair< Vector, Matrix > result = self->return_pair(v,A);
mxArray* mxh = mxGetProperty(in[0],0,"self");
Shared* self = *reinterpret_cast<Shared**> (mxGetPr(mxh));
Shared obj = *self;
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);
}

View File

@ -1,5 +1,4 @@
% automatically generated by wrap
% [first,second] = obj.return_pair(v,A)
function [first,second] = return_pair(obj,v,A)
% usage: obj.return_pair(v,A)
error('need to compile return_pair.cpp');
end

View File

@ -1,14 +1,22 @@
// automatically generated by wrap
#include <wrap/matlab.h>
#include <set>
#include <folder/path/to/Test.h>
using namespace geometry;
typedef boost::shared_ptr<Test> SharedTest;
typedef boost::shared_ptr<Test> SharedTest;
typedef boost::shared_ptr<Test> Shared;
void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
checkArguments("return_ptrs",nargout,nargin-1,2);
boost::shared_ptr<Test> self = unwrap_shared_ptr< Test >(in[0],"Test");
mxArray* mxh = mxGetProperty(in[0],0,"self");
Shared* self = *reinterpret_cast<Shared**> (mxGetPr(mxh));
Shared obj = *self;
boost::shared_ptr<Test> p1 = unwrap_shared_ptr< Test >(in[1], "Test");
boost::shared_ptr<Test> p2 = unwrap_shared_ptr< Test >(in[2], "Test");
pair< boost::shared_ptr<Test>, boost::shared_ptr<Test> > result = self->return_ptrs(p1,p2);
out[0] = wrap_shared_ptr(result.first,"Test");
out[1] = wrap_shared_ptr(result.second,"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");
}

View File

@ -1,5 +1,4 @@
% automatically generated by wrap
% [first,second] = obj.return_ptrs(p1,p2)
function [first,second] = return_ptrs(obj,p1,p2)
% usage: obj.return_ptrs(p1,p2)
error('need to compile return_ptrs.cpp');
end

View File

@ -1,12 +1,16 @@
// automatically generated by wrap
#include <wrap/matlab.h>
#include <set>
#include <folder/path/to/Test.h>
using namespace geometry;
typedef boost::shared_ptr<Test> Shared;
void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
checkArguments("return_size_t",nargout,nargin-1,1);
boost::shared_ptr<Test> self = unwrap_shared_ptr< Test >(in[0],"Test");
size_t value = unwrap< size_t >(in[1]);
size_t result = self->return_size_t(value);
mxArray* mxh = mxGetProperty(in[0],0,"self");
Shared* self = *reinterpret_cast<Shared**> (mxGetPr(mxh));
Shared obj = *self;
size_t value = unwrap< size_t >(in[1]);
size_t result = obj->return_size_t(value);
out[0] = wrap< size_t >(result);
}

View File

@ -1,5 +1,4 @@
% automatically generated by wrap
% result = obj.return_size_t(value)
function result = return_size_t(obj,value)
% usage: obj.return_size_t(value)
error('need to compile return_size_t.cpp');
end

View File

@ -1,12 +1,16 @@
// automatically generated by wrap
#include <wrap/matlab.h>
#include <set>
#include <folder/path/to/Test.h>
using namespace geometry;
typedef boost::shared_ptr<Test> Shared;
void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
checkArguments("return_string",nargout,nargin-1,1);
boost::shared_ptr<Test> self = unwrap_shared_ptr< Test >(in[0],"Test");
string value = unwrap< string >(in[1]);
string result = self->return_string(value);
mxArray* mxh = mxGetProperty(in[0],0,"self");
Shared* self = *reinterpret_cast<Shared**> (mxGetPr(mxh));
Shared obj = *self;
string value = unwrap< string >(in[1]);
string result = obj->return_string(value);
out[0] = wrap< string >(result);
}

View File

@ -1,5 +1,4 @@
% automatically generated by wrap
% result = obj.return_string(value)
function result = return_string(obj,value)
% usage: obj.return_string(value)
error('need to compile return_string.cpp');
end

View File

@ -1,12 +1,16 @@
// automatically generated by wrap
#include <wrap/matlab.h>
#include <set>
#include <folder/path/to/Test.h>
using namespace geometry;
typedef boost::shared_ptr<Test> Shared;
void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
checkArguments("return_vector1",nargout,nargin-1,1);
boost::shared_ptr<Test> self = unwrap_shared_ptr< Test >(in[0],"Test");
Vector value = unwrap< Vector >(in[1]);
Vector result = self->return_vector1(value);
mxArray* mxh = mxGetProperty(in[0],0,"self");
Shared* self = *reinterpret_cast<Shared**> (mxGetPr(mxh));
Shared obj = *self;
Vector value = unwrap< Vector >(in[1]);
Vector result = obj->return_vector1(value);
out[0] = wrap< Vector >(result);
}

View File

@ -1,5 +1,4 @@
% automatically generated by wrap
% result = obj.return_vector1(value)
function result = return_vector1(obj,value)
% usage: obj.return_vector1(value)
error('need to compile return_vector1.cpp');
end

View File

@ -1,12 +1,16 @@
// automatically generated by wrap
#include <wrap/matlab.h>
#include <set>
#include <folder/path/to/Test.h>
using namespace geometry;
typedef boost::shared_ptr<Test> Shared;
void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
checkArguments("return_vector2",nargout,nargin-1,1);
boost::shared_ptr<Test> self = unwrap_shared_ptr< Test >(in[0],"Test");
Vector value = unwrap< Vector >(in[1]);
Vector result = self->return_vector2(value);
mxArray* mxh = mxGetProperty(in[0],0,"self");
Shared* self = *reinterpret_cast<Shared**> (mxGetPr(mxh));
Shared obj = *self;
Vector value = unwrap< Vector >(in[1]);
Vector result = obj->return_vector2(value);
out[0] = wrap< Vector >(result);
}

View File

@ -1,5 +1,4 @@
% automatically generated by wrap
% result = obj.return_vector2(value)
function result = return_vector2(obj,value)
% usage: obj.return_vector2(value)
error('need to compile return_vector2.cpp');
end

View File

@ -2,95 +2,86 @@
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
new_Point2_.$(MEXENDING): new_Point2_.cpp $(PATH_TO_WRAP)/matlab.h
$(MEX) $(mex_flags) new_Point2_.cpp -output new_Point2_
new_Point2_dd.$(MEXENDING): new_Point2_dd.cpp
$(MEX) $(mex_flags) new_Point2_dd.cpp -output new_Point2_dd
delete_Point2.$(MEXENDING): delete_Point2.cpp
$(MEX) $(mex_flags) delete_Point2.cpp -output delete_Point2
@Point2/x.$(MEXENDING): @Point2/x.cpp
@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
@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
@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
@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
@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
@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
@Point2/vectorConfusion.$(MEXENDING): @Point2/vectorConfusion.cpp $(PATH_TO_WRAP)/matlab.h
$(MEX) $(mex_flags) @Point2/vectorConfusion.cpp -output @Point2/vectorConfusion
Point2: new_Point2_.$(MEXENDING) new_Point2_dd.$(MEXENDING) delete_Point2.$(MEXENDING) @Point2/x.$(MEXENDING) @Point2/y.$(MEXENDING) @Point2/dim.$(MEXENDING) @Point2/returnChar.$(MEXENDING) @Point2/argChar.$(MEXENDING) @Point2/argUChar.$(MEXENDING) @Point2/vectorConfusion.$(MEXENDING)
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_ddd.$(MEXENDING): new_Point3_ddd.cpp
$(MEX) $(mex_flags) new_Point3_ddd.cpp -output new_Point3_ddd
delete_Point3.$(MEXENDING): delete_Point3.cpp
$(MEX) $(mex_flags) delete_Point3.cpp -output delete_Point3
Point3_staticFunction.$(MEXENDING): Point3_staticFunction.cpp
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
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
@Point3/norm.$(MEXENDING): @Point3/norm.cpp $(PATH_TO_WRAP)/matlab.h
$(MEX) $(mex_flags) @Point3/norm.cpp -output @Point3/norm
Point3: new_Point3_ddd.$(MEXENDING) delete_Point3.$(MEXENDING) Point3_staticFunction.$(MEXENDING) Point3_StaticFunctionRet.$(MEXENDING) @Point3/norm.$(MEXENDING)
Point3: new_Point3_.$(MEXENDING) Point3_staticFunction.$(MEXENDING) Point3_StaticFunctionRet.$(MEXENDING) @Point3/norm.$(MEXENDING)
# Test
new_Test_.$(MEXENDING): new_Test_.cpp
new_Test_.$(MEXENDING): new_Test_.cpp $(PATH_TO_WRAP)/matlab.h
$(MEX) $(mex_flags) new_Test_.cpp -output new_Test_
new_Test_dM.$(MEXENDING): new_Test_dM.cpp
$(MEX) $(mex_flags) new_Test_dM.cpp -output new_Test_dM
delete_Test.$(MEXENDING): delete_Test.cpp
$(MEX) $(mex_flags) delete_Test.cpp -output delete_Test
@Test/return_pair.$(MEXENDING): @Test/return_pair.cpp
@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
@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
@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
@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
@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
@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
@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
@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
@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
@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
@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
@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
@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
@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
@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
@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
@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
@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
@Test/print.$(MEXENDING): @Test/print.cpp $(PATH_TO_WRAP)/matlab.h
$(MEX) $(mex_flags) @Test/print.cpp -output @Test/print
Test: new_Test_.$(MEXENDING) new_Test_dM.$(MEXENDING) delete_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)
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)

View File

@ -1,11 +1,15 @@
// automatically generated by wrap
#include <wrap/matlab.h>
#include <set>
#include <Point3.h>
using namespace geometry;
typedef boost::shared_ptr<Point3> SharedPoint3;
typedef boost::shared_ptr<Point3> Shared;
void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
checkArguments("Point3_StaticFunctionRet",nargout,nargin,1);
double z = unwrap< double >(in[0]);
double z = unwrap< double >(in[0]);
Point3 result = Point3::StaticFunctionRet(z);
out[0] = wrap_shared_ptr(boost::make_shared< Point3 >(result),"Point3");
SharedPoint3* ret = new SharedPoint3(new Point3(result));
out[0] = wrap_collect_shared_ptr(ret,"Point3");
}

View File

@ -1,7 +1,10 @@
// automatically generated by wrap
#include <wrap/matlab.h>
#include <set>
#include <Point3.h>
using namespace geometry;
typedef boost::shared_ptr<double> Shareddouble;
typedef boost::shared_ptr<Point3> Shared;
void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
checkArguments("Point3_staticFunction",nargout,nargin,0);

View File

@ -1,8 +0,0 @@
// automatically generated by wrap
#include <wrap/matlab.h>
#include <Point2.h>
void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
checkArguments("delete_Point2",nargout,nargin,1);
delete_shared_ptr< Point2 >(in[0],"Point2");
}

View File

@ -1,4 +0,0 @@
% automatically generated by wrap
function result = delete_Point2(obj)
error('need to compile delete_Point2.cpp');
end

View File

@ -1,9 +0,0 @@
// automatically generated by wrap
#include <wrap/matlab.h>
#include <Point3.h>
using namespace geometry;
void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
checkArguments("delete_Point3",nargout,nargin,1);
delete_shared_ptr< Point3 >(in[0],"Point3");
}

View File

@ -1,4 +0,0 @@
% automatically generated by wrap
function result = delete_Point3(obj)
error('need to compile delete_Point3.cpp');
end

View File

@ -1,9 +0,0 @@
// automatically generated by wrap
#include <wrap/matlab.h>
#include <folder/path/to/Test.h>
using namespace geometry;
void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
checkArguments("delete_Test",nargout,nargin,1);
delete_shared_ptr< Test >(in[0],"Test");
}

View File

@ -1,4 +0,0 @@
% automatically generated by wrap
function result = delete_Test(obj)
error('need to compile delete_Test.cpp');
end

View File

@ -10,8 +10,6 @@ addpath(toolboxpath);
%% Point2
cd(toolboxpath)
mex -O5 new_Point2_.cpp
mex -O5 new_Point2_dd.cpp
mex -O5 delete_Point2.cpp
cd @Point2
mex -O5 x.cpp
@ -24,8 +22,7 @@ mex -O5 vectorConfusion.cpp
%% Point3
cd(toolboxpath)
mex -O5 new_Point3_ddd.cpp
mex -O5 delete_Point3.cpp
mex -O5 new_Point3_.cpp
mex -O5 Point3_staticFunction.cpp
mex -O5 Point3_StaticFunctionRet.cpp
@ -35,8 +32,6 @@ mex -O5 norm.cpp
%% Test
cd(toolboxpath)
mex -O5 new_Test_.cpp
mex -O5 new_Test_dM.cpp
mex -O5 delete_Test.cpp
cd @Test
mex -O5 return_pair.cpp

View File

@ -1,9 +1,47 @@
// automatically generated by wrap
#include <wrap/matlab.h>
#include <set>
#include <Point2.h>
typedef boost::shared_ptr<Point2> Shared;
static std::set<Shared*> collector;
struct Destruct
{
void operator() (Shared* p)
{
collector.erase(p);
}
};
void cleanup(void) {
std::for_each( collector.begin(), collector.end(), Destruct() );
}
void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
checkArguments("new_Point2_",nargout,nargin,0);
Point2* self = new Point2();
out[0] = wrap_constructed(self,"Point2");
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<int>(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<Shared**> (mxGetPr(out[0])) = self;
}
}

View File

@ -1,4 +1,4 @@
% automatically generated by wrap
function result = new_Point2_(obj)
function result = new_Point2_(obj,x,y)
error('need to compile new_Point2_.cpp');
end

View File

@ -1,11 +0,0 @@
// automatically generated by wrap
#include <wrap/matlab.h>
#include <Point2.h>
void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
checkArguments("new_Point2_dd",nargout,nargin,2);
double x = unwrap< double >(in[0]);
double y = unwrap< double >(in[1]);
Point2* self = new Point2(x,y);
out[0] = wrap_constructed(self,"Point2");
}

View File

@ -1,4 +0,0 @@
% automatically generated by wrap
function result = new_Point2_dd(obj,x,y)
error('need to compile new_Point2_dd.cpp');
end

View File

@ -0,0 +1,46 @@
// automatically generated by wrap
#include <wrap/matlab.h>
#include <set>
#include <Point3.h>
using namespace geometry;
typedef boost::shared_ptr<Point3> Shared;
static std::set<Shared*> collector;
struct Destruct
{
void operator() (Shared* p)
{
collector.erase(p);
}
};
void cleanup(void) {
std::for_each( collector.begin(), collector.end(), Destruct() );
}
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<int>(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<Shared**> (mxGetPr(out[0])) = self;
}
}

View File

@ -0,0 +1,4 @@
% automatically generated by wrap
function result = new_Point3_(obj,x,y,z)
error('need to compile new_Point3_.cpp');
end

View File

@ -1,13 +0,0 @@
// automatically generated by wrap
#include <wrap/matlab.h>
#include <Point3.h>
using namespace geometry;
void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
checkArguments("new_Point3_ddd",nargout,nargin,3);
double x = unwrap< double >(in[0]);
double y = unwrap< double >(in[1]);
double z = unwrap< double >(in[2]);
Point3* self = new Point3(x,y,z);
out[0] = wrap_constructed(self,"Point3");
}

View File

@ -1,4 +0,0 @@
% automatically generated by wrap
function result = new_Point3_ddd(obj,x,y,z)
error('need to compile new_Point3_ddd.cpp');
end

View File

@ -1,10 +1,48 @@
// automatically generated by wrap
#include <wrap/matlab.h>
#include <set>
#include <folder/path/to/Test.h>
using namespace geometry;
typedef boost::shared_ptr<Test> Shared;
static std::set<Shared*> collector;
struct Destruct
{
void operator() (Shared* p)
{
collector.erase(p);
}
};
void cleanup(void) {
std::for_each( collector.begin(), collector.end(), Destruct() );
}
void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
checkArguments("new_Test_",nargout,nargin,0);
Test* self = new Test();
out[0] = wrap_constructed(self,"Test");
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<int>(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<Shared**> (mxGetPr(out[0])) = self;
}
}

View File

@ -1,4 +1,4 @@
% automatically generated by wrap
function result = new_Test_(obj)
function result = new_Test_(obj,a,b)
error('need to compile new_Test_.cpp');
end

View File

@ -1,12 +0,0 @@
// automatically generated by wrap
#include <wrap/matlab.h>
#include <folder/path/to/Test.h>
using namespace geometry;
void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
checkArguments("new_Test_dM",nargout,nargin,2);
double a = unwrap< double >(in[0]);
Matrix b = unwrap< Matrix >(in[1]);
Test* self = new Test(a,b);
out[0] = wrap_constructed(self,"Test");
}

View File

@ -1,4 +0,0 @@
% automatically generated by wrap
function result = new_Test_dM(obj,a,b)
error('need to compile new_Test_dM.cpp');
end

View File

@ -5,11 +5,15 @@ classdef ClassD < handle
end
methods
function obj = ClassD(varargin)
if (nargin == 0), obj.self = new_ClassD_(); end
if nargin ~= 13 && obj.self == 0, error('ClassD constructor failed'); end
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)
delete_ClassD(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

View File

@ -5,11 +5,15 @@ classdef ns1ClassA < handle
end
methods
function obj = ns1ClassA(varargin)
if (nargin == 0), obj.self = new_ns1ClassA_(); end
if nargin ~= 13 && obj.self == 0, error('ns1ClassA constructor failed'); end
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)
delete_ns1ClassA(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

View File

@ -5,11 +5,15 @@ classdef ns1ClassB < handle
end
methods
function obj = ns1ClassB(varargin)
if (nargin == 0), obj.self = new_ns1ClassB_(); end
if nargin ~= 13 && obj.self == 0, error('ns1ClassB constructor failed'); end
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)
delete_ns1ClassB(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

Some files were not shown because too many files have changed in this diff Show More