Removed from wrap the use of "using namespace xxx" statements - wasn't fully supported before, and now we have real namespace support
parent
79c9bc99ff
commit
656f573c0a
3
gtsam.h
3
gtsam.h
|
@ -41,9 +41,6 @@
|
|||
* 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: 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
|
||||
* - All includes will be collected and added in a single file
|
||||
* - All namespaces must have angle brackets: <path>
|
||||
|
|
|
@ -79,7 +79,7 @@ void Class::matlab_proxy(const string& toolboxPath, const string& wrapperName,
|
|||
const int id = (int)functionNames.size();
|
||||
constructor.proxy_fragment(proxyFile, wrapperName, !qualifiedParent.empty(), id, a);
|
||||
const string wrapFunctionName = constructor.wrapper_fragment(wrapperFile,
|
||||
cppName, matlabUniqueName, cppBaseName, id, using_namespaces, a);
|
||||
cppName, matlabUniqueName, cppBaseName, id, a);
|
||||
wrapperFile.oss << "\n";
|
||||
functionNames.push_back(wrapFunctionName);
|
||||
}
|
||||
|
@ -96,7 +96,7 @@ void Class::matlab_proxy(const string& toolboxPath, const string& wrapperName,
|
|||
const int id = (int)functionNames.size();
|
||||
deconstructor.proxy_fragment(proxyFile, wrapperName, matlabUniqueName, id);
|
||||
proxyFile.oss << "\n";
|
||||
const string functionName = deconstructor.wrapper_fragment(wrapperFile, cppName, matlabUniqueName, id, using_namespaces);
|
||||
const string functionName = deconstructor.wrapper_fragment(wrapperFile, cppName, matlabUniqueName, id);
|
||||
wrapperFile.oss << "\n";
|
||||
functionNames.push_back(functionName);
|
||||
}
|
||||
|
@ -106,7 +106,7 @@ void Class::matlab_proxy(const string& toolboxPath, const string& wrapperName,
|
|||
// Methods
|
||||
BOOST_FOREACH(const Methods::value_type& name_m, methods) {
|
||||
const Method& m = name_m.second;
|
||||
m.proxy_wrapper_fragments(proxyFile, wrapperFile, cppName, matlabQualName, matlabUniqueName, wrapperName, using_namespaces, typeAttributes, functionNames);
|
||||
m.proxy_wrapper_fragments(proxyFile, wrapperFile, cppName, matlabQualName, matlabUniqueName, wrapperName, typeAttributes, functionNames);
|
||||
proxyFile.oss << "\n";
|
||||
wrapperFile.oss << "\n";
|
||||
}
|
||||
|
@ -118,7 +118,7 @@ void Class::matlab_proxy(const string& toolboxPath, const string& wrapperName,
|
|||
// 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, matlabQualName, matlabUniqueName, wrapperName, using_namespaces, typeAttributes, functionNames);
|
||||
m.proxy_wrapper_fragments(proxyFile, wrapperFile, cppName, matlabQualName, matlabUniqueName, wrapperName, typeAttributes, functionNames);
|
||||
proxyFile.oss << "\n";
|
||||
wrapperFile.oss << "\n";
|
||||
}
|
||||
|
@ -183,7 +183,6 @@ void Class::pointer_constructor_fragments(FileWriter& proxyFile, FileWriter& wra
|
|||
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";
|
||||
|
@ -273,7 +272,6 @@ Class expandClassTemplate(const Class& cls, const string& templateArg, const vec
|
|||
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;
|
||||
inst.constructor = cls.constructor;
|
||||
inst.constructor.args_list = expandArgumentListsTemplate(cls.constructor.args_list, templateArg, instName);
|
||||
inst.constructor.name = inst.name;
|
||||
|
|
|
@ -47,7 +47,6 @@ struct Class {
|
|||
Methods methods; ///< Class methods
|
||||
StaticMethods static_methods; ///< Static methods
|
||||
std::vector<std::string> namespaces; ///< Stack of namespaces
|
||||
std::vector<std::string> using_namespaces;///< default namespaces
|
||||
Constructor constructor; ///< Class constructors
|
||||
Deconstructor deconstructor; ///< Deconstructor to deallocate C++ object
|
||||
bool verbose_; ///< verbose flag
|
||||
|
|
|
@ -70,7 +70,6 @@ string Constructor::wrapper_fragment(FileWriter& file,
|
|||
const string& matlabUniqueName,
|
||||
const string& cppBaseClassName,
|
||||
int id,
|
||||
const vector<string>& using_namespaces,
|
||||
const ArgumentList& al) const {
|
||||
|
||||
const string wrapFunctionName = matlabUniqueName + "_constructor_" + boost::lexical_cast<string>(id);
|
||||
|
@ -78,7 +77,6 @@ string Constructor::wrapper_fragment(FileWriter& file,
|
|||
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;\n";
|
||||
file.oss << "\n";
|
||||
|
|
|
@ -58,7 +58,6 @@ struct Constructor {
|
|||
const std::string& matlabUniqueName,
|
||||
const std::string& cppBaseClassName,
|
||||
int id,
|
||||
const std::vector<std::string>& using_namespaces,
|
||||
const ArgumentList& al) const;
|
||||
|
||||
/// constructor function
|
||||
|
|
|
@ -48,8 +48,7 @@ void Deconstructor::proxy_fragment(FileWriter& file,
|
|||
string Deconstructor::wrapper_fragment(FileWriter& file,
|
||||
const string& cppClassName,
|
||||
const string& matlabUniqueName,
|
||||
int id,
|
||||
const vector<string>& using_namespaces) const {
|
||||
int id) const {
|
||||
|
||||
const string matlabName = matlab_wrapper_name(matlabUniqueName);
|
||||
|
||||
|
@ -57,7 +56,6 @@ string Deconstructor::wrapper_fragment(FileWriter& file,
|
|||
|
||||
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;
|
||||
|
|
|
@ -54,8 +54,7 @@ struct Deconstructor {
|
|||
std::string wrapper_fragment(FileWriter& file,
|
||||
const std::string& cppClassName,
|
||||
const std::string& matlabUniqueName,
|
||||
int id,
|
||||
const std::vector<std::string>& using_namespaces) const;
|
||||
int id) const;
|
||||
};
|
||||
|
||||
} // \namespace wrap
|
||||
|
|
|
@ -42,7 +42,6 @@ void Method::proxy_wrapper_fragments(FileWriter& proxyFile, FileWriter& wrapperF
|
|||
const std::string& matlabQualName,
|
||||
const std::string& matlabUniqueName,
|
||||
const string& wrapperName,
|
||||
const vector<string>& using_namespaces,
|
||||
const TypeAttributesTable& typeAttributes,
|
||||
vector<string>& functionNames) const {
|
||||
|
||||
|
@ -82,7 +81,7 @@ void Method::proxy_wrapper_fragments(FileWriter& proxyFile, FileWriter& wrapperF
|
|||
// Output C++ wrapper code
|
||||
|
||||
const string wrapFunctionName = wrapper_fragment(
|
||||
wrapperFile, cppClassName, matlabUniqueName, overload, id, using_namespaces, typeAttributes);
|
||||
wrapperFile, cppClassName, matlabUniqueName, overload, id, typeAttributes);
|
||||
|
||||
// Add to function list
|
||||
functionNames.push_back(wrapFunctionName);
|
||||
|
@ -103,7 +102,6 @@ string Method::wrapper_fragment(FileWriter& file,
|
|||
const string& matlabUniqueName,
|
||||
int overload,
|
||||
int id,
|
||||
const vector<string>& using_namespaces,
|
||||
const TypeAttributesTable& typeAttributes) const {
|
||||
|
||||
// generate code
|
||||
|
@ -117,7 +115,6 @@ string Method::wrapper_fragment(FileWriter& file,
|
|||
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)
|
||||
{
|
||||
|
|
|
@ -51,8 +51,7 @@ struct Method {
|
|||
// classPath is class directory, e.g., ../matlab/@Point2
|
||||
void proxy_wrapper_fragments(FileWriter& proxyFile, FileWriter& wrapperFile,
|
||||
const std::string& cppClassName, const std::string& matlabQualName, const std::string& matlabUniqueName,
|
||||
const std::string& wrapperName, const std::vector<std::string>& using_namespaces,
|
||||
const TypeAttributesTable& typeAttributes,
|
||||
const std::string& wrapperName, const TypeAttributesTable& typeAttributes,
|
||||
std::vector<std::string>& functionNames) const;
|
||||
|
||||
private:
|
||||
|
@ -61,7 +60,6 @@ private:
|
|||
const std::string& matlabUniqueName,
|
||||
int overload,
|
||||
int id,
|
||||
const std::vector<std::string>& using_namespaces,
|
||||
const TypeAttributesTable& typeAttributes) const; ///< cpp wrapper
|
||||
};
|
||||
|
||||
|
|
|
@ -84,8 +84,7 @@ Module::Module(const string& interfacePath,
|
|||
GlobalFunction globalFunc0(enable_verbose), globalFunc(enable_verbose);
|
||||
ForwardDeclaration fwDec0, fwDec;
|
||||
vector<string> namespaces, /// current namespace tag
|
||||
namespaces_return, /// namespace for current return type
|
||||
using_namespace_current; /// All namespaces from "using" declarations
|
||||
namespaces_return; /// namespace for current return type
|
||||
string templateArgument;
|
||||
vector<string> templateInstantiationNamespace;
|
||||
vector<vector<string> > templateInstantiations;
|
||||
|
@ -264,7 +263,6 @@ Module::Module(const string& interfacePath,
|
|||
[assign_a(constructor.name, cls.name)]
|
||||
[assign_a(cls.constructor, constructor)]
|
||||
[assign_a(cls.namespaces, namespaces)]
|
||||
[assign_a(cls.using_namespaces, using_namespace_current)]
|
||||
[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))]
|
||||
|
@ -298,10 +296,6 @@ Module::Module(const string& interfacePath,
|
|||
>> ch_p('}'))
|
||||
[pop_a(namespaces)];
|
||||
|
||||
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")
|
||||
|
@ -310,7 +304,7 @@ Module::Module(const string& interfacePath,
|
|||
[push_back_a(forward_declarations, fwDec)]
|
||||
[assign_a(fwDec, fwDec0)];
|
||||
|
||||
Rule module_content_p = comments_p | using_namespace_p | include_p | class_p | templateSingleInstantiation_p | forward_declaration_p | global_function_p | namespace_def_p;
|
||||
Rule module_content_p = comments_p | include_p | class_p | templateSingleInstantiation_p | forward_declaration_p | global_function_p | namespace_def_p;
|
||||
|
||||
Rule module_p = *module_content_p >> !end_p;
|
||||
|
||||
|
|
|
@ -44,7 +44,6 @@ void StaticMethod::proxy_wrapper_fragments(FileWriter& proxyFile, FileWriter& wr
|
|||
const std::string& matlabQualName,
|
||||
const std::string& matlabUniqueName,
|
||||
const string& wrapperName,
|
||||
const vector<string>& using_namespaces,
|
||||
const TypeAttributesTable& typeAttributes,
|
||||
vector<string>& functionNames) const {
|
||||
|
||||
|
@ -86,7 +85,7 @@ void StaticMethod::proxy_wrapper_fragments(FileWriter& proxyFile, FileWriter& wr
|
|||
// Output C++ wrapper code
|
||||
|
||||
const string wrapFunctionName = wrapper_fragment(
|
||||
wrapperFile, cppClassName, matlabUniqueName, overload, id, using_namespaces, typeAttributes);
|
||||
wrapperFile, cppClassName, matlabUniqueName, overload, id, typeAttributes);
|
||||
|
||||
// Add to function list
|
||||
functionNames.push_back(wrapFunctionName);
|
||||
|
@ -107,7 +106,6 @@ string StaticMethod::wrapper_fragment(FileWriter& file,
|
|||
const string& matlabUniqueName,
|
||||
int overload,
|
||||
int id,
|
||||
const vector<string>& using_namespaces,
|
||||
const TypeAttributesTable& typeAttributes) const {
|
||||
|
||||
// generate code
|
||||
|
@ -121,7 +119,6 @@ string StaticMethod::wrapper_fragment(FileWriter& file,
|
|||
file.oss << "void " << wrapFunctionName << "(int nargout, mxArray *out[], int nargin, const mxArray *in[])\n";
|
||||
// start
|
||||
file.oss << "{\n";
|
||||
generateUsingNamespace(file, using_namespaces);
|
||||
|
||||
returnVal.wrapTypeUnwrap(file);
|
||||
|
||||
|
|
|
@ -51,8 +51,7 @@ struct StaticMethod {
|
|||
// classPath is class directory, e.g., ../matlab/@Point2
|
||||
void proxy_wrapper_fragments(FileWriter& proxyFile, FileWriter& wrapperFile,
|
||||
const std::string& cppClassName, const std::string& matlabQualName, const std::string& matlabUniqueName,
|
||||
const std::string& wrapperName, const std::vector<std::string>& using_namespaces,
|
||||
const TypeAttributesTable& typeAttributes,
|
||||
const std::string& wrapperName, const TypeAttributesTable& typeAttributes,
|
||||
std::vector<std::string>& functionNames) const;
|
||||
|
||||
private:
|
||||
|
@ -61,7 +60,6 @@ private:
|
|||
const std::string& matlabUniqueName,
|
||||
int overload,
|
||||
int id,
|
||||
const std::vector<std::string>& using_namespaces,
|
||||
const TypeAttributesTable& typeAttributes) const; ///< cpp wrapper
|
||||
};
|
||||
|
||||
|
|
|
@ -180,7 +180,6 @@ void Point2_y_10(int nargout, mxArray *out[], int nargin, const mxArray *in[])
|
|||
void Point3_collectorInsertAndMakeBase_11(int nargout, mxArray *out[], int nargin, const mxArray *in[])
|
||||
{
|
||||
mexAtExit(&_deleteAllObjects);
|
||||
using namespace geometry;
|
||||
typedef boost::shared_ptr<Point3> Shared;
|
||||
|
||||
Shared *self = *reinterpret_cast<Shared**> (mxGetData(in[0]));
|
||||
|
@ -190,7 +189,6 @@ using namespace geometry;
|
|||
void Point3_constructor_12(int nargout, mxArray *out[], int nargin, const mxArray *in[])
|
||||
{
|
||||
mexAtExit(&_deleteAllObjects);
|
||||
using namespace geometry;
|
||||
typedef boost::shared_ptr<Point3> Shared;
|
||||
|
||||
double x = unwrap< double >(in[0]);
|
||||
|
@ -204,7 +202,6 @@ using namespace geometry;
|
|||
|
||||
void Point3_deconstructor_13(int nargout, mxArray *out[], int nargin, const mxArray *in[])
|
||||
{
|
||||
using namespace geometry;
|
||||
typedef boost::shared_ptr<Point3> Shared;
|
||||
checkArguments("delete_Point3",nargout,nargin,1);
|
||||
Shared *self = *reinterpret_cast<Shared**>(mxGetData(in[0]));
|
||||
|
@ -218,7 +215,6 @@ using namespace geometry;
|
|||
|
||||
void Point3_norm_14(int nargout, mxArray *out[], int nargin, const mxArray *in[])
|
||||
{
|
||||
using namespace geometry;
|
||||
typedef boost::shared_ptr<Point3> Shared;
|
||||
checkArguments("norm",nargout,nargin-1,0);
|
||||
Shared obj = unwrap_shared_ptr<Point3>(in[0], "ptr_Point3");
|
||||
|
@ -227,7 +223,6 @@ using namespace geometry;
|
|||
|
||||
void Point3_StaticFunctionRet_15(int nargout, mxArray *out[], int nargin, const mxArray *in[])
|
||||
{
|
||||
using namespace geometry;
|
||||
typedef boost::shared_ptr<Point3> SharedPoint3;
|
||||
typedef boost::shared_ptr<Point3> Shared;
|
||||
checkArguments("Point3.StaticFunctionRet",nargout,nargin,1);
|
||||
|
@ -237,7 +232,6 @@ using namespace geometry;
|
|||
|
||||
void Point3_staticFunction_16(int nargout, mxArray *out[], int nargin, const mxArray *in[])
|
||||
{
|
||||
using namespace geometry;
|
||||
typedef boost::shared_ptr<Point3> Shared;
|
||||
checkArguments("Point3.staticFunction",nargout,nargin,0);
|
||||
out[0] = wrap< double >(Point3::staticFunction());
|
||||
|
@ -246,7 +240,6 @@ using namespace geometry;
|
|||
void Test_collectorInsertAndMakeBase_17(int nargout, mxArray *out[], int nargin, const mxArray *in[])
|
||||
{
|
||||
mexAtExit(&_deleteAllObjects);
|
||||
using namespace geometry;
|
||||
typedef boost::shared_ptr<Test> Shared;
|
||||
|
||||
Shared *self = *reinterpret_cast<Shared**> (mxGetData(in[0]));
|
||||
|
@ -256,7 +249,6 @@ using namespace geometry;
|
|||
void Test_constructor_18(int nargout, mxArray *out[], int nargin, const mxArray *in[])
|
||||
{
|
||||
mexAtExit(&_deleteAllObjects);
|
||||
using namespace geometry;
|
||||
typedef boost::shared_ptr<Test> Shared;
|
||||
|
||||
Shared *self = new Shared(new Test());
|
||||
|
@ -268,7 +260,6 @@ using namespace geometry;
|
|||
void Test_constructor_19(int nargout, mxArray *out[], int nargin, const mxArray *in[])
|
||||
{
|
||||
mexAtExit(&_deleteAllObjects);
|
||||
using namespace geometry;
|
||||
typedef boost::shared_ptr<Test> Shared;
|
||||
|
||||
double a = unwrap< double >(in[0]);
|
||||
|
@ -281,7 +272,6 @@ using namespace geometry;
|
|||
|
||||
void Test_deconstructor_20(int nargout, mxArray *out[], int nargin, const mxArray *in[])
|
||||
{
|
||||
using namespace geometry;
|
||||
typedef boost::shared_ptr<Test> Shared;
|
||||
checkArguments("delete_Test",nargout,nargin,1);
|
||||
Shared *self = *reinterpret_cast<Shared**>(mxGetData(in[0]));
|
||||
|
@ -295,7 +285,6 @@ using namespace geometry;
|
|||
|
||||
void Test_arg_EigenConstRef_21(int nargout, mxArray *out[], int nargin, const mxArray *in[])
|
||||
{
|
||||
using namespace geometry;
|
||||
typedef boost::shared_ptr<Test> Shared;
|
||||
checkArguments("arg_EigenConstRef",nargout,nargin-1,1);
|
||||
Shared obj = unwrap_shared_ptr<Test>(in[0], "ptr_Test");
|
||||
|
@ -305,7 +294,6 @@ using namespace geometry;
|
|||
|
||||
void Test_create_MixedPtrs_22(int nargout, mxArray *out[], int nargin, const mxArray *in[])
|
||||
{
|
||||
using namespace geometry;
|
||||
typedef boost::shared_ptr<Test> SharedTest;
|
||||
typedef boost::shared_ptr<Test> SharedTest;
|
||||
typedef boost::shared_ptr<Test> Shared;
|
||||
|
@ -317,7 +305,6 @@ using namespace geometry;
|
|||
|
||||
void Test_create_ptrs_23(int nargout, mxArray *out[], int nargin, const mxArray *in[])
|
||||
{
|
||||
using namespace geometry;
|
||||
typedef boost::shared_ptr<Test> SharedTest;
|
||||
typedef boost::shared_ptr<Test> SharedTest;
|
||||
typedef boost::shared_ptr<Test> Shared;
|
||||
|
@ -329,7 +316,6 @@ using namespace geometry;
|
|||
|
||||
void Test_print_24(int nargout, mxArray *out[], int nargin, const mxArray *in[])
|
||||
{
|
||||
using namespace geometry;
|
||||
typedef boost::shared_ptr<Test> Shared;
|
||||
checkArguments("print",nargout,nargin-1,0);
|
||||
Shared obj = unwrap_shared_ptr<Test>(in[0], "ptr_Test");
|
||||
|
@ -338,7 +324,6 @@ using namespace geometry;
|
|||
|
||||
void Test_return_Point2Ptr_25(int nargout, mxArray *out[], int nargin, const mxArray *in[])
|
||||
{
|
||||
using namespace geometry;
|
||||
typedef boost::shared_ptr<Point2> SharedPoint2;
|
||||
typedef boost::shared_ptr<Test> Shared;
|
||||
checkArguments("return_Point2Ptr",nargout,nargin-1,1);
|
||||
|
@ -349,7 +334,6 @@ using namespace geometry;
|
|||
|
||||
void Test_return_Test_26(int nargout, mxArray *out[], int nargin, const mxArray *in[])
|
||||
{
|
||||
using namespace geometry;
|
||||
typedef boost::shared_ptr<Test> SharedTest;
|
||||
typedef boost::shared_ptr<Test> Shared;
|
||||
checkArguments("return_Test",nargout,nargin-1,1);
|
||||
|
@ -360,7 +344,6 @@ using namespace geometry;
|
|||
|
||||
void Test_return_TestPtr_27(int nargout, mxArray *out[], int nargin, const mxArray *in[])
|
||||
{
|
||||
using namespace geometry;
|
||||
typedef boost::shared_ptr<Test> SharedTest;
|
||||
typedef boost::shared_ptr<Test> Shared;
|
||||
checkArguments("return_TestPtr",nargout,nargin-1,1);
|
||||
|
@ -371,7 +354,6 @@ using namespace geometry;
|
|||
|
||||
void Test_return_bool_28(int nargout, mxArray *out[], int nargin, const mxArray *in[])
|
||||
{
|
||||
using namespace geometry;
|
||||
typedef boost::shared_ptr<Test> Shared;
|
||||
checkArguments("return_bool",nargout,nargin-1,1);
|
||||
Shared obj = unwrap_shared_ptr<Test>(in[0], "ptr_Test");
|
||||
|
@ -381,7 +363,6 @@ using namespace geometry;
|
|||
|
||||
void Test_return_double_29(int nargout, mxArray *out[], int nargin, const mxArray *in[])
|
||||
{
|
||||
using namespace geometry;
|
||||
typedef boost::shared_ptr<Test> Shared;
|
||||
checkArguments("return_double",nargout,nargin-1,1);
|
||||
Shared obj = unwrap_shared_ptr<Test>(in[0], "ptr_Test");
|
||||
|
@ -391,7 +372,6 @@ using namespace geometry;
|
|||
|
||||
void Test_return_field_30(int nargout, mxArray *out[], int nargin, const mxArray *in[])
|
||||
{
|
||||
using namespace geometry;
|
||||
typedef boost::shared_ptr<Test> Shared;
|
||||
checkArguments("return_field",nargout,nargin-1,1);
|
||||
Shared obj = unwrap_shared_ptr<Test>(in[0], "ptr_Test");
|
||||
|
@ -401,7 +381,6 @@ using namespace geometry;
|
|||
|
||||
void Test_return_int_31(int nargout, mxArray *out[], int nargin, const mxArray *in[])
|
||||
{
|
||||
using namespace geometry;
|
||||
typedef boost::shared_ptr<Test> Shared;
|
||||
checkArguments("return_int",nargout,nargin-1,1);
|
||||
Shared obj = unwrap_shared_ptr<Test>(in[0], "ptr_Test");
|
||||
|
@ -411,7 +390,6 @@ using namespace geometry;
|
|||
|
||||
void Test_return_matrix1_32(int nargout, mxArray *out[], int nargin, const mxArray *in[])
|
||||
{
|
||||
using namespace geometry;
|
||||
typedef boost::shared_ptr<Test> Shared;
|
||||
checkArguments("return_matrix1",nargout,nargin-1,1);
|
||||
Shared obj = unwrap_shared_ptr<Test>(in[0], "ptr_Test");
|
||||
|
@ -421,7 +399,6 @@ using namespace geometry;
|
|||
|
||||
void Test_return_matrix2_33(int nargout, mxArray *out[], int nargin, const mxArray *in[])
|
||||
{
|
||||
using namespace geometry;
|
||||
typedef boost::shared_ptr<Test> Shared;
|
||||
checkArguments("return_matrix2",nargout,nargin-1,1);
|
||||
Shared obj = unwrap_shared_ptr<Test>(in[0], "ptr_Test");
|
||||
|
@ -431,7 +408,6 @@ using namespace geometry;
|
|||
|
||||
void Test_return_pair_34(int nargout, mxArray *out[], int nargin, const mxArray *in[])
|
||||
{
|
||||
using namespace geometry;
|
||||
typedef boost::shared_ptr<Test> Shared;
|
||||
checkArguments("return_pair",nargout,nargin-1,2);
|
||||
Shared obj = unwrap_shared_ptr<Test>(in[0], "ptr_Test");
|
||||
|
@ -443,7 +419,6 @@ using namespace geometry;
|
|||
|
||||
void Test_return_ptrs_35(int nargout, mxArray *out[], int nargin, const mxArray *in[])
|
||||
{
|
||||
using namespace geometry;
|
||||
typedef boost::shared_ptr<Test> SharedTest;
|
||||
typedef boost::shared_ptr<Test> SharedTest;
|
||||
typedef boost::shared_ptr<Test> Shared;
|
||||
|
@ -457,7 +432,6 @@ using namespace geometry;
|
|||
|
||||
void Test_return_size_t_36(int nargout, mxArray *out[], int nargin, const mxArray *in[])
|
||||
{
|
||||
using namespace geometry;
|
||||
typedef boost::shared_ptr<Test> Shared;
|
||||
checkArguments("return_size_t",nargout,nargin-1,1);
|
||||
Shared obj = unwrap_shared_ptr<Test>(in[0], "ptr_Test");
|
||||
|
@ -467,7 +441,6 @@ using namespace geometry;
|
|||
|
||||
void Test_return_string_37(int nargout, mxArray *out[], int nargin, const mxArray *in[])
|
||||
{
|
||||
using namespace geometry;
|
||||
typedef boost::shared_ptr<Test> Shared;
|
||||
checkArguments("return_string",nargout,nargin-1,1);
|
||||
Shared obj = unwrap_shared_ptr<Test>(in[0], "ptr_Test");
|
||||
|
@ -477,7 +450,6 @@ using namespace geometry;
|
|||
|
||||
void Test_return_vector1_38(int nargout, mxArray *out[], int nargin, const mxArray *in[])
|
||||
{
|
||||
using namespace geometry;
|
||||
typedef boost::shared_ptr<Test> Shared;
|
||||
checkArguments("return_vector1",nargout,nargin-1,1);
|
||||
Shared obj = unwrap_shared_ptr<Test>(in[0], "ptr_Test");
|
||||
|
@ -487,7 +459,6 @@ using namespace geometry;
|
|||
|
||||
void Test_return_vector2_39(int nargout, mxArray *out[], int nargin, const mxArray *in[])
|
||||
{
|
||||
using namespace geometry;
|
||||
typedef boost::shared_ptr<Test> Shared;
|
||||
checkArguments("return_vector2",nargout,nargin-1,1);
|
||||
Shared obj = unwrap_shared_ptr<Test>(in[0], "ptr_Test");
|
||||
|
|
|
@ -15,9 +15,6 @@ class Point2 {
|
|||
VectorNotEigen vectorConfusion();
|
||||
};
|
||||
|
||||
// flag a namespace as in use - only applies *after* the declaration
|
||||
using namespace geometry;
|
||||
|
||||
class Point3 {
|
||||
Point3(double x, double y, double z);
|
||||
double norm() const;
|
||||
|
|
|
@ -76,9 +76,6 @@ TEST( wrap, parse_geometry ) {
|
|||
Module module(markup_header_path.c_str(), "geometry",enable_verbose);
|
||||
EXPECT_LONGS_EQUAL(3, module.classes.size());
|
||||
|
||||
// check using declarations
|
||||
strvec exp_using1, exp_using2; exp_using2 += "geometry";
|
||||
|
||||
// forward declarations
|
||||
LONGS_EQUAL(2, module.forward_declarations.size());
|
||||
EXPECT(assert_equal("VectorNotEigen", module.forward_declarations[0].name));
|
||||
|
@ -98,7 +95,6 @@ TEST( wrap, parse_geometry ) {
|
|||
EXPECT_LONGS_EQUAL(7, cls.methods.size());
|
||||
EXPECT_LONGS_EQUAL(0, cls.static_methods.size());
|
||||
EXPECT_LONGS_EQUAL(0, cls.namespaces.size());
|
||||
EXPECT(assert_equal(exp_using1, cls.using_namespaces));
|
||||
}
|
||||
|
||||
// check second class, Point3
|
||||
|
@ -109,7 +105,6 @@ TEST( wrap, parse_geometry ) {
|
|||
EXPECT_LONGS_EQUAL(1, cls.methods.size());
|
||||
EXPECT_LONGS_EQUAL(2, cls.static_methods.size());
|
||||
EXPECT_LONGS_EQUAL(0, cls.namespaces.size());
|
||||
EXPECT(assert_equal(exp_using2, cls.using_namespaces));
|
||||
|
||||
// first constructor takes 3 doubles
|
||||
ArgumentList c1 = cls.constructor.args_list.front();
|
||||
|
@ -140,7 +135,6 @@ TEST( wrap, parse_geometry ) {
|
|||
EXPECT_LONGS_EQUAL(19, testCls.methods.size());
|
||||
EXPECT_LONGS_EQUAL( 0, testCls.static_methods.size());
|
||||
EXPECT_LONGS_EQUAL( 0, testCls.namespaces.size());
|
||||
EXPECT(assert_equal(exp_using2, testCls.using_namespaces));
|
||||
|
||||
// function to parse: pair<Vector,Matrix> return_pair (Vector v, Matrix A) const;
|
||||
CHECK(testCls.methods.find("return_pair") != testCls.methods.end());
|
||||
|
|
|
@ -115,13 +115,6 @@ string maybe_shared_ptr(bool add, const string& qtype, const string& type) {
|
|||
return str;
|
||||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
void generateUsingNamespace(FileWriter& file, const vector<string>& using_namespaces) {
|
||||
if (using_namespaces.empty()) return;
|
||||
BOOST_FOREACH(const string& s, using_namespaces)
|
||||
file.oss << "using namespace " << s << ";" << endl;
|
||||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
string qualifiedName(const string& separator, const vector<string>& names, const string& finalName) {
|
||||
string result;
|
||||
|
|
|
@ -122,11 +122,6 @@ bool assert_equal(const std::vector<std::string>& expected, const std::vector<st
|
|||
// auxiliary function to wrap an argument into a shared_ptr template
|
||||
std::string maybe_shared_ptr(bool add, const std::string& qtype, const std::string& type);
|
||||
|
||||
/**
|
||||
* Creates the "using namespace [name];" declarations
|
||||
*/
|
||||
void generateUsingNamespace(FileWriter& file, const std::vector<std::string>& using_namespaces);
|
||||
|
||||
/**
|
||||
* 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).
|
||||
|
|
Loading…
Reference in New Issue