From 52a85f23f8dce7a07917245c396a87a73d5b103a Mon Sep 17 00:00:00 2001 From: Duy-Nguyen Ta Date: Mon, 21 Nov 2016 17:14:30 -0500 Subject: [PATCH] fix bugs on returned values --- cython/gtsam.h | 2 +- wrap/Constructor.cpp | 2 +- wrap/Method.cpp | 4 ++-- wrap/OverloadedFunction.h | 8 +++++--- wrap/StaticMethod.cpp | 2 +- 5 files changed, 10 insertions(+), 8 deletions(-) diff --git a/cython/gtsam.h b/cython/gtsam.h index d70fd7382..8ffd19003 100644 --- a/cython/gtsam.h +++ b/cython/gtsam.h @@ -1756,7 +1756,7 @@ class NonlinearFactorGraph { #include virtual class NoiseModelFactor: gtsam::NonlinearFactor { - void equals(const gtsam::NoiseModelFactor& other, double tol) const; + bool equals(const gtsam::NoiseModelFactor& other, double tol) const; gtsam::noiseModel::Base* get_noiseModel() const; // deprecated by below gtsam::noiseModel::Base* noiseModel() const; Vector unwhitenedError(const gtsam::Values& x) const; diff --git a/wrap/Constructor.cpp b/wrap/Constructor.cpp index 9a5f3993a..b9b9e8068 100644 --- a/wrap/Constructor.cpp +++ b/wrap/Constructor.cpp @@ -147,7 +147,7 @@ void Constructor::emit_cython_pyx(FileWriter& pyxFile, const Class& cls) const { ArgumentList args = argumentList(i); pyxFile.oss << "\tdef " + name_ + "_" + to_string(i) + "(self, *args, **kwargs):\n"; - pyxFile.oss << pyx_resolveOverloadParams(args); + pyxFile.oss << pyx_resolveOverloadParams(args, true); pyxFile.oss << "\t\tself." << cls.pyxCythonObj() << " = " << cls.pyxSharedCythonClass() << "(new " << cls.pyxCythonClass() diff --git a/wrap/Method.cpp b/wrap/Method.cpp index c317688ab..f54670259 100644 --- a/wrap/Method.cpp +++ b/wrap/Method.cpp @@ -166,13 +166,13 @@ void Method::emit_cython_pyx(FileWriter& file, const Class& cls) const { ArgumentList args = argumentList(i); file.oss << "\tdef " + instantiatedName + "_" + to_string(i) + "(self, *args, **kwargs):\n"; - file.oss << pyx_resolveOverloadParams(args); + file.oss << pyx_resolveOverloadParams(args, false); // lazy: always return None even if it's a void function /// Call cython corresponding function string caller = "self." + cls.pyxCythonObj() + ".get()"; string ret = pyx_functionCall(caller, funcName, i); - if (!returnVals_[0].isVoid()) { + if (!returnVals_[i].isVoid()) { file.oss << "\t\tcdef " << returnVals_[i].pyx_returnType() << " ret = " << ret << "\n"; file.oss << "\t\treturn True, " << returnVals_[i].pyx_casting("ret") << "\n"; diff --git a/wrap/OverloadedFunction.h b/wrap/OverloadedFunction.h index f33df313e..27e5f9b09 100644 --- a/wrap/OverloadedFunction.h +++ b/wrap/OverloadedFunction.h @@ -71,10 +71,11 @@ public: return os; } - std::string pyx_resolveOverloadParams(const ArgumentList& args) const { + std::string pyx_resolveOverloadParams(const ArgumentList& args, bool isVoid) const { std::string s; s += "\t\tif len(args)+len(kwargs) !=" + std::to_string(args.size()) + ":\n"; - s += "\t\t\treturn False\n"; + s += "\t\t\treturn False"; + s += (!isVoid) ? ", None\n" : "\n"; if (args.size() > 0) { s += "\t\t__params = kwargs.copy()\n"; s += "\t\t__names = [" + args.pyx_paramsList() + "]\n"; @@ -83,7 +84,8 @@ public: s += "\t\ttry:\n"; s += args.pyx_castParamsToPythonType(); s += "\t\texcept:\n"; - s += "\t\t\treturn False\n"; + s += "\t\t\treturn False"; + s += (!isVoid) ? ", None\n" : "\n"; } return s; } diff --git a/wrap/StaticMethod.cpp b/wrap/StaticMethod.cpp index a1662ff7d..d64f79733 100644 --- a/wrap/StaticMethod.cpp +++ b/wrap/StaticMethod.cpp @@ -115,7 +115,7 @@ void StaticMethod::emit_cython_pyx(FileWriter& file, const Class& cls) const { string pxdFuncName = name_ + ((i>0)?"_" + to_string(i):""); ArgumentList args = argumentList(i); file.oss << "\tdef " + funcName + "(*args, **kwargs):\n"; - file.oss << pyx_resolveOverloadParams(args); + file.oss << pyx_resolveOverloadParams(args, false); // lazy: always return None even if it's a void function /// Call cython corresponding function and return string ret = pyx_functionCall(cls.pyxCythonClass(), pxdFuncName, i);