unify and simplify function call in Method and StaticMethod
parent
63a5d1e15a
commit
fabfac65f4
|
@ -95,6 +95,7 @@ void Method::emit_cython_pyx(FileWriter& file, const Class& cls) const {
|
||||||
string funcName = ((name_ == "print") ? "_print" : name_);
|
string funcName = ((name_ == "print") ? "_print" : name_);
|
||||||
size_t N = nrOverloads();
|
size_t N = nrOverloads();
|
||||||
for(size_t i = 0; i < N; ++i) {
|
for(size_t i = 0; i < N; ++i) {
|
||||||
|
// Function definition
|
||||||
file.oss << "\tdef " << funcName;
|
file.oss << "\tdef " << funcName;
|
||||||
// modify name of function instantiation as python doesn't allow overloads
|
// modify name of function instantiation as python doesn't allow overloads
|
||||||
// e.g. template<T={A,B,C}> funcName(...) --> funcNameA, funcNameB, funcNameC
|
// e.g. template<T={A,B,C}> funcName(...) --> funcNameA, funcNameB, funcNameC
|
||||||
|
@ -109,25 +110,9 @@ void Method::emit_cython_pyx(FileWriter& file, const Class& cls) const {
|
||||||
argumentList(i).emit_cython_pyx(file);
|
argumentList(i).emit_cython_pyx(file);
|
||||||
file.oss << "):\n";
|
file.oss << "):\n";
|
||||||
|
|
||||||
/// Return part
|
/// Call cython corresponding function and return
|
||||||
file.oss << "\t\t";
|
string caller = "self." + cls.pyxCythonObj() + ".get()";
|
||||||
if (!returnVals_[i].isVoid()) {
|
emit_cython_pyx_function_call(file, "\t\t", caller, funcName, i, cls);
|
||||||
file.oss << "cdef ";
|
|
||||||
returnVals_[i].emit_cython_pyx_return_type(file);
|
|
||||||
file.oss << " ret = ";
|
|
||||||
}
|
|
||||||
//... function call
|
|
||||||
file.oss << "self." << cls.pyxCythonObj() << ".get()." << funcName;
|
|
||||||
if (templateArgValue_) file.oss << "[" << templateArgValue_->pyxCythonClass() << "]";
|
|
||||||
file.oss << "(";
|
|
||||||
argumentList(i).emit_cython_pyx_asParams(file);
|
|
||||||
file.oss << ")\n";
|
|
||||||
|
|
||||||
file.oss << "\t\t";
|
|
||||||
if (!returnVals_[i].isVoid()) file.oss << "return ";
|
|
||||||
// ... casting return value
|
|
||||||
returnVals_[i].emit_cython_pyx_casting(file, "ret");
|
|
||||||
file.oss << "\n";
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
/* ************************************************************************* */
|
/* ************************************************************************* */
|
||||||
|
|
|
@ -22,9 +22,6 @@
|
||||||
|
|
||||||
namespace wrap {
|
namespace wrap {
|
||||||
|
|
||||||
// Forward declaration
|
|
||||||
class Class;
|
|
||||||
|
|
||||||
/// Method class
|
/// Method class
|
||||||
class Method: public MethodBase {
|
class Method: public MethodBase {
|
||||||
|
|
||||||
|
|
|
@ -17,6 +17,7 @@
|
||||||
**/
|
**/
|
||||||
|
|
||||||
#include "Method.h"
|
#include "Method.h"
|
||||||
|
#include "Class.h"
|
||||||
#include "utilities.h"
|
#include "utilities.h"
|
||||||
|
|
||||||
#include <boost/lexical_cast.hpp>
|
#include <boost/lexical_cast.hpp>
|
||||||
|
@ -138,3 +139,32 @@ void MethodBase::python_wrapper(FileWriter& wrapperFile, Str className) const {
|
||||||
}
|
}
|
||||||
|
|
||||||
/* ************************************************************************* */
|
/* ************************************************************************* */
|
||||||
|
void MethodBase::emit_cython_pyx_function_call(FileWriter& file,
|
||||||
|
const std::string& indent,
|
||||||
|
const std::string& caller,
|
||||||
|
const std::string& funcName,
|
||||||
|
size_t iOverload,
|
||||||
|
const Class& cls) const {
|
||||||
|
file.oss << indent;
|
||||||
|
if (!returnVals_[iOverload].isVoid()) {
|
||||||
|
file.oss << "cdef ";
|
||||||
|
returnVals_[iOverload].emit_cython_pyx_return_type(file);
|
||||||
|
file.oss << " ret = ";
|
||||||
|
}
|
||||||
|
//... function call
|
||||||
|
file.oss << caller << "." << funcName;
|
||||||
|
if (templateArgValue_) file.oss << "[" << templateArgValue_->pyxCythonClass() << "]";
|
||||||
|
file.oss << "(";
|
||||||
|
argumentList(iOverload).emit_cython_pyx_asParams(file);
|
||||||
|
file.oss << ")\n";
|
||||||
|
|
||||||
|
// ... casting return value
|
||||||
|
if (!returnVals_[iOverload].isVoid()) {
|
||||||
|
file.oss << indent;
|
||||||
|
file.oss << "return ";
|
||||||
|
returnVals_[iOverload].emit_cython_pyx_casting(file, "ret");
|
||||||
|
}
|
||||||
|
file.oss << "\n";
|
||||||
|
}
|
||||||
|
|
||||||
|
/* ************************************************************************* */
|
||||||
|
|
|
@ -23,6 +23,9 @@
|
||||||
|
|
||||||
namespace wrap {
|
namespace wrap {
|
||||||
|
|
||||||
|
// Forward declaration
|
||||||
|
class Class;
|
||||||
|
|
||||||
/// MethodBase class
|
/// MethodBase class
|
||||||
struct MethodBase: public FullyOverloadedFunction {
|
struct MethodBase: public FullyOverloadedFunction {
|
||||||
|
|
||||||
|
@ -51,6 +54,14 @@ struct MethodBase: public FullyOverloadedFunction {
|
||||||
// emit python wrapper
|
// emit python wrapper
|
||||||
void python_wrapper(FileWriter& wrapperFile, Str className) const;
|
void python_wrapper(FileWriter& wrapperFile, Str className) const;
|
||||||
|
|
||||||
|
// emit cython pyx function call
|
||||||
|
void emit_cython_pyx_function_call(FileWriter& file,
|
||||||
|
const std::string& indent,
|
||||||
|
const std::string& caller,
|
||||||
|
const std::string& funcName,
|
||||||
|
size_t iOverload,
|
||||||
|
const Class& cls) const;
|
||||||
|
|
||||||
protected:
|
protected:
|
||||||
|
|
||||||
virtual void proxy_header(FileWriter& proxyFile) const = 0;
|
virtual void proxy_header(FileWriter& proxyFile) const = 0;
|
||||||
|
|
|
@ -75,26 +75,14 @@ void StaticMethod::emit_cython_pxd(FileWriter& file) const {
|
||||||
void StaticMethod::emit_cython_pyx(FileWriter& file, const Class& cls) const {
|
void StaticMethod::emit_cython_pyx(FileWriter& file, const Class& cls) const {
|
||||||
// don't support overloads for static method :-(
|
// don't support overloads for static method :-(
|
||||||
for(size_t i = 0; i < nrOverloads(); ++i) {
|
for(size_t i = 0; i < nrOverloads(); ++i) {
|
||||||
|
string funcName = name_ + ((i>0)? "_" + to_string(i):"");
|
||||||
file.oss << "\t@staticmethod\n";
|
file.oss << "\t@staticmethod\n";
|
||||||
file.oss << "\tdef " << name_ << ((i > 0) ? "_" + to_string(i) : "")
|
file.oss << "\tdef " << funcName << "(";
|
||||||
<< "(";
|
|
||||||
argumentList(i).emit_cython_pyx(file);
|
argumentList(i).emit_cython_pyx(file);
|
||||||
file.oss << "):\n";
|
file.oss << "):\n";
|
||||||
file.oss << "\t\t";
|
|
||||||
//... function call
|
|
||||||
if (!returnVals_[i].isVoid()) file.oss << "ret = ";
|
|
||||||
file.oss << cls.pyxCythonClass() << "."
|
|
||||||
<< name_ << ((i>0)? "_" + to_string(i):"");
|
|
||||||
if (templateArgValue_) file.oss << "[" << templateArgValue_->pyxCythonClass() << "]";
|
|
||||||
file.oss << "(";
|
|
||||||
argumentList(i).emit_cython_pyx_asParams(file);
|
|
||||||
file.oss << ")\n";
|
|
||||||
|
|
||||||
//... casting return value
|
/// Call cython corresponding function and return
|
||||||
if (!returnVals_[i].isVoid()) {
|
emit_cython_pyx_function_call(file, "\t\t", cls.pyxCythonClass(), funcName, i, cls);
|
||||||
file.oss << "\t\treturn ";
|
|
||||||
returnVals_[i].emit_cython_pyx_casting(file, "ret");
|
|
||||||
}
|
|
||||||
file.oss << "\n";
|
file.oss << "\n";
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
|
@ -23,9 +23,6 @@
|
||||||
|
|
||||||
namespace wrap {
|
namespace wrap {
|
||||||
|
|
||||||
// Forward declaration
|
|
||||||
class Class;
|
|
||||||
|
|
||||||
/// StaticMethod class
|
/// StaticMethod class
|
||||||
struct StaticMethod: public MethodBase {
|
struct StaticMethod: public MethodBase {
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue