proper overloading constructors
parent
dc185a6d30
commit
acf3c9d259
|
@ -10,6 +10,7 @@ template<T> class FastVector {
|
||||||
void push_back(const T& e);
|
void push_back(const T& e);
|
||||||
//T& operator[](int);
|
//T& operator[](int);
|
||||||
T at(int i);
|
T at(int i);
|
||||||
|
size_t size() const;
|
||||||
};
|
};
|
||||||
|
|
||||||
typedef gtsam::FastVector<gtsam::Key> KeyVector;
|
typedef gtsam::FastVector<gtsam::Key> KeyVector;
|
||||||
|
|
|
@ -23,7 +23,7 @@ Rmat = np.array([
|
||||||
[0.104218, 0.990074, -0.0942928],
|
[0.104218, 0.990074, -0.0942928],
|
||||||
[-0.0942928, 0.104218, 0.990074]
|
[-0.0942928, 0.104218, 0.990074]
|
||||||
])
|
])
|
||||||
r5 = Rot3.Rot3_1(Rmat)
|
r5 = Rot3(R=Rmat)
|
||||||
r5.print_(b"r5: ")
|
r5.print_(b"r5: ")
|
||||||
|
|
||||||
l = Rot3.Logmap(r5)
|
l = Rot3.Logmap(r5)
|
||||||
|
@ -41,7 +41,7 @@ print("diag R:", diag.R())
|
||||||
|
|
||||||
p = Point3()
|
p = Point3()
|
||||||
p.print_("p:")
|
p.print_("p:")
|
||||||
factor = BetweenFactorPoint3.BetweenFactorPoint3(1,2,p, noise)
|
factor = BetweenFactorPoint3(1,2,p, noise)
|
||||||
factor.print_(b"factor:")
|
factor.print_(b"factor:")
|
||||||
|
|
||||||
vv = VectorValues()
|
vv = VectorValues()
|
||||||
|
@ -51,7 +51,7 @@ vv.insert(2, np.array([3.,4.]))
|
||||||
vv.insert(3, np.array([5.,6.,7.,8.]))
|
vv.insert(3, np.array([5.,6.,7.,8.]))
|
||||||
vv.print_(b"vv:")
|
vv.print_(b"vv:")
|
||||||
|
|
||||||
vv2 = VectorValues.VectorValues_1(vv)
|
vv2 = VectorValues(vv)
|
||||||
vv2.insert(4, np.array([4.,2.,1]))
|
vv2.insert(4, np.array([4.,2.,1]))
|
||||||
vv2.print_(b"vv2:")
|
vv2.print_(b"vv2:")
|
||||||
vv.print_(b"vv:")
|
vv.print_(b"vv:")
|
||||||
|
@ -67,5 +67,5 @@ values.insertPoint3(1, Point3())
|
||||||
values.insertRot3(2, Rot3())
|
values.insertRot3(2, Rot3())
|
||||||
values.print_(b"values:")
|
values.print_(b"values:")
|
||||||
|
|
||||||
factor = PriorFactorVector.PriorFactorVector(1, np.array([1.,2.,3.]), diag)
|
factor = PriorFactorVector(1, np.array([1.,2.,3.]), diag)
|
||||||
factor.print_("Prior factor vector: ")
|
print "Prior factor vector: ", factor
|
||||||
|
|
|
@ -117,11 +117,7 @@ void Argument::emit_cython_pxd(FileWriter& file, const std::string& className) c
|
||||||
|
|
||||||
/* ************************************************************************* */
|
/* ************************************************************************* */
|
||||||
void Argument::emit_cython_pyx(FileWriter& file) const {
|
void Argument::emit_cython_pyx(FileWriter& file) const {
|
||||||
string typeName = type.pythonClass();
|
file.oss << type.pythonArgumentType() << " " << name;
|
||||||
string cythonType = typeName;
|
|
||||||
// use numpy for Vector and Matrix
|
|
||||||
if (type.isEigen()) cythonType = "np.ndarray";
|
|
||||||
file.oss << cythonType << " " << name;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
/* ************************************************************************* */
|
/* ************************************************************************* */
|
||||||
|
@ -236,12 +232,34 @@ void ArgumentList::emit_cython_pyx(FileWriter& file) const {
|
||||||
|
|
||||||
/* ************************************************************************* */
|
/* ************************************************************************* */
|
||||||
void ArgumentList::emit_cython_pyx_asParams(FileWriter& file) const {
|
void ArgumentList::emit_cython_pyx_asParams(FileWriter& file) const {
|
||||||
for (size_t j = 0; j < size(); ++j) {
|
for (size_t j = 0; j < size(); ++j) {
|
||||||
at(j).emit_cython_pyx_asParam(file);
|
at(j).emit_cython_pyx_asParam(file);
|
||||||
if (j < size() - 1) file.oss << ", ";
|
if (j < size() - 1) file.oss << ", ";
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
/* ************************************************************************* */
|
||||||
|
void ArgumentList::emit_cython_pyx_params_list(FileWriter& file) const {
|
||||||
|
for (size_t j = 0; j < size(); ++j) {
|
||||||
|
file.oss << "'" << at(j).name << "'";
|
||||||
|
if (j < size() - 1) file.oss << ", ";
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
/* ************************************************************************* */
|
||||||
|
void ArgumentList::emit_cython_pyx_cast_params_to_python_type(FileWriter& file) const {
|
||||||
|
if (size() == 0) {
|
||||||
|
file.oss << "\t\t\tpass\n";
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
// cast params to their correct python argument type to pass in the function call later
|
||||||
|
for (size_t j = 0; j < size(); ++j) {
|
||||||
|
file.oss << "\t\t\t" << at(j).name << " = <" << at(j).type.pythonArgumentType()
|
||||||
|
<< ">(__params['" << at(j).name << "'])\n";
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
/* ************************************************************************* */
|
/* ************************************************************************* */
|
||||||
void ArgumentList::proxy_check(FileWriter& proxyFile) const {
|
void ArgumentList::proxy_check(FileWriter& proxyFile) const {
|
||||||
// Check nr of arguments
|
// Check nr of arguments
|
||||||
|
|
|
@ -127,6 +127,8 @@ struct ArgumentList: public std::vector<Argument> {
|
||||||
void emit_cython_pxd(FileWriter& file, const std::string& className) const;
|
void emit_cython_pxd(FileWriter& file, const std::string& className) const;
|
||||||
void emit_cython_pyx(FileWriter& file) const;
|
void emit_cython_pyx(FileWriter& file) const;
|
||||||
void emit_cython_pyx_asParams(FileWriter& file) const;
|
void emit_cython_pyx_asParams(FileWriter& file) const;
|
||||||
|
void emit_cython_pyx_params_list(FileWriter& file) const;
|
||||||
|
void emit_cython_pyx_cast_params_to_python_type(FileWriter& file) const;
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* emit checking arguments to MATLAB proxy
|
* emit checking arguments to MATLAB proxy
|
||||||
|
|
|
@ -19,6 +19,7 @@
|
||||||
#include "Class.h"
|
#include "Class.h"
|
||||||
#include "utilities.h"
|
#include "utilities.h"
|
||||||
#include "Argument.h"
|
#include "Argument.h"
|
||||||
|
#include <unordered_set>
|
||||||
|
|
||||||
#include <boost/lexical_cast.hpp>
|
#include <boost/lexical_cast.hpp>
|
||||||
#include <boost/range/adaptor/map.hpp>
|
#include <boost/range/adaptor/map.hpp>
|
||||||
|
@ -794,13 +795,48 @@ void Class::emit_cython_pyx(FileWriter& pyxFile, const std::vector<Class>& allCl
|
||||||
pyxFile.oss << "\tcdef " << pyxSharedCythonClass() << " " << pyxCythonObj() << "\n";
|
pyxFile.oss << "\tcdef " << pyxSharedCythonClass() << " " << pyxCythonObj() << "\n";
|
||||||
|
|
||||||
// __cinit___
|
// __cinit___
|
||||||
pyxFile.oss << "\tdef __cinit__(self):\n"
|
pyxFile.oss << "\tdef __cinit__(self, *args, **kwargs):\n"
|
||||||
"\t\tself." << pyxCythonObj() << " = "
|
"\t\tself." << pyxCythonObj() << " = "
|
||||||
<< pyxSharedCythonClass() << "(";
|
<< pyxSharedCythonClass() << "()\n";
|
||||||
if (constructor.hasDefaultConstructor())
|
|
||||||
pyxFile.oss << "new " << pyxCythonClass() << "()";
|
std::unordered_set<size_t> nargsSet;
|
||||||
pyxFile.oss << ")\n";
|
std::vector<size_t> nargsDuplicates;
|
||||||
|
for (size_t i = 0; i < constructor.nrOverloads(); ++i) {
|
||||||
|
size_t nargs = constructor.argumentList(i).size();
|
||||||
|
if (nargsSet.find(nargs) != nargsSet.end())
|
||||||
|
nargsDuplicates.push_back(nargs);
|
||||||
|
else
|
||||||
|
nargsSet.insert(nargs);
|
||||||
|
}
|
||||||
|
|
||||||
|
if (nargsDuplicates.size() > 0) {
|
||||||
|
pyxFile.oss << "\t\tif len(kwargs)==0 and len(args)+len(kwargs) in [";
|
||||||
|
for (size_t i = 0; i<nargsDuplicates.size(); ++i) {
|
||||||
|
pyxFile.oss << nargsDuplicates[i];
|
||||||
|
if (i < nargsDuplicates.size()-1) pyxFile.oss << ",";
|
||||||
|
}
|
||||||
|
pyxFile.oss << "]:\n"
|
||||||
|
<< "\t\t\traise TypeError('Overloads with the same number of "
|
||||||
|
"arguments exist. Please use keyword arguments to "
|
||||||
|
"differentiate them!')\n";
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
for (size_t i = 0; i<constructor.nrOverloads(); ++i) {
|
||||||
|
pyxFile.oss << "\t\t" << (i == 0 ? "if" : "elif") << " self."
|
||||||
|
<< pythonClass() << "_" << i
|
||||||
|
<< "(*args, **kwargs):\n\t\t\tpass\n";
|
||||||
|
}
|
||||||
|
if (constructor.nrOverloads()>0)
|
||||||
|
pyxFile.oss << "\t\telse:\n\t\t\traise TypeError('" << pythonClass()
|
||||||
|
<< " construction failed!')\n";
|
||||||
|
|
||||||
pyxInitParentObj(pyxFile, "\t\tself", "self." + pyxCythonObj(), allClasses);
|
pyxInitParentObj(pyxFile, "\t\tself", "self." + pyxCythonObj(), allClasses);
|
||||||
|
pyxFile.oss << "\n";
|
||||||
|
|
||||||
|
// Constructors
|
||||||
|
constructor.emit_cython_pyx(pyxFile, *this);
|
||||||
|
if (constructor.nrOverloads()>0) pyxFile.oss << "\n";
|
||||||
|
|
||||||
// cyCreateFromShared
|
// cyCreateFromShared
|
||||||
pyxFile.oss << "\t@staticmethod\n";
|
pyxFile.oss << "\t@staticmethod\n";
|
||||||
|
@ -811,10 +847,6 @@ void Class::emit_cython_pyx(FileWriter& pyxFile, const std::vector<Class>& allCl
|
||||||
pyxInitParentObj(pyxFile, "\t\tret", "other", allClasses);
|
pyxInitParentObj(pyxFile, "\t\tret", "other", allClasses);
|
||||||
pyxFile.oss << "\t\treturn ret" << "\n";
|
pyxFile.oss << "\t\treturn ret" << "\n";
|
||||||
|
|
||||||
// Constructors
|
|
||||||
constructor.emit_cython_pyx(pyxFile, *this);
|
|
||||||
if (constructor.nrOverloads()>0) pyxFile.oss << "\n";
|
|
||||||
|
|
||||||
for(const StaticMethod& m: static_methods | boost::adaptors::map_values)
|
for(const StaticMethod& m: static_methods | boost::adaptors::map_values)
|
||||||
m.emit_cython_pyx(pyxFile, *this);
|
m.emit_cython_pyx(pyxFile, *this);
|
||||||
if (static_methods.size()>0) pyxFile.oss << "\n";
|
if (static_methods.size()>0) pyxFile.oss << "\n";
|
||||||
|
|
|
@ -1,6 +1,6 @@
|
||||||
/* ----------------------------------------------------------------------------
|
/* ----------------------------------------------------------------------------
|
||||||
|
|
||||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||||
* Atlanta, Georgia 30332-0415
|
* Atlanta, Georgia 30332-0415
|
||||||
* All Rights Reserved
|
* All Rights Reserved
|
||||||
* Authors: Frank Dellaert, et al. (see THANKS for the full author list)
|
* Authors: Frank Dellaert, et al. (see THANKS for the full author list)
|
||||||
|
@ -125,7 +125,7 @@ void Constructor::python_wrapper(FileWriter& wrapperFile, Str className) const {
|
||||||
bool Constructor::hasDefaultConstructor() const {
|
bool Constructor::hasDefaultConstructor() const {
|
||||||
for (size_t i = 0; i < nrOverloads(); i++) {
|
for (size_t i = 0; i < nrOverloads(); i++) {
|
||||||
if (argumentList(i).size() == 0) return true;
|
if (argumentList(i).size() == 0) return true;
|
||||||
}
|
}
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -143,26 +143,30 @@ void Constructor::emit_cython_pxd(FileWriter& pxdFile, Str className) const {
|
||||||
|
|
||||||
/* ************************************************************************* */
|
/* ************************************************************************* */
|
||||||
void Constructor::emit_cython_pyx(FileWriter& pyxFile, const Class& cls) const {
|
void Constructor::emit_cython_pyx(FileWriter& pyxFile, const Class& cls) const {
|
||||||
// FIXME: handle overloads properly! This is lazy...
|
|
||||||
for (size_t i = 0; i < nrOverloads(); i++) {
|
for (size_t i = 0; i < nrOverloads(); i++) {
|
||||||
ArgumentList args = argumentList(i);
|
ArgumentList args = argumentList(i);
|
||||||
pyxFile.oss << "\t@staticmethod\n";
|
pyxFile.oss << "\tdef " << name_ << "_" + to_string(i) << "(self, *args, **kwargs):\n";
|
||||||
pyxFile.oss << "\tdef " << name_
|
pyxFile.oss << "\t\tif len(args)+len(kwargs) !=" << args.size() << ":\n";
|
||||||
<< ((i > 0) ? "_" + to_string(i) : "") << "(";
|
pyxFile.oss << "\t\t\treturn False\n";
|
||||||
args.emit_cython_pyx(pyxFile);
|
if (args.size() > 0) {
|
||||||
pyxFile.oss << "): \n";
|
pyxFile.oss << "\t\t__params = kwargs.copy()\n"
|
||||||
|
"\t\t__names = [";
|
||||||
|
args.emit_cython_pyx_params_list(pyxFile);
|
||||||
|
pyxFile.oss << "]\n";
|
||||||
|
pyxFile.oss << "\t\tfor i in range(len(args)):\n"
|
||||||
|
"\t\t\t__params[__names[i]] = args[i]\n";
|
||||||
|
pyxFile.oss << "\t\ttry:\n";
|
||||||
|
args.emit_cython_pyx_cast_params_to_python_type(pyxFile);
|
||||||
|
pyxFile.oss << "\t\texcept:\n"
|
||||||
|
"\t\t\treturn False\n";
|
||||||
|
}
|
||||||
|
|
||||||
// Don't use cyCreateFromValue because the class might not have
|
pyxFile.oss << "\t\tself." << cls.pyxCythonObj() << " = "
|
||||||
// copy constructor and copy assignment operator!!
|
<< cls.pyxSharedCythonClass() << "(new " << cls.pyxCythonClass()
|
||||||
// For example: noiseModel::Robust doesn't have the copy assignment operator
|
<< "(";
|
||||||
// because its members are shared_ptr to abstract base classes. That fails
|
|
||||||
// Cython to generate the object as it assigns the new obj to a temp variable.
|
|
||||||
pyxFile.oss << "\t\treturn " << cls.cythonClass()
|
|
||||||
<< ".cyCreateFromShared(" << cls.pyxSharedCythonClass()
|
|
||||||
<< "(new " << cls.pyxCythonClass() << "(";
|
|
||||||
args.emit_cython_pyx_asParams(pyxFile);
|
args.emit_cython_pyx_asParams(pyxFile);
|
||||||
pyxFile.oss << "))"
|
pyxFile.oss << "))\n";
|
||||||
<< ")\n";
|
pyxFile.oss << "\t\treturn True\n\n";
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue