Skip to content

Commit

Permalink
Merge pull request #165 from borglab/remove-matrix-assumptions
Browse files Browse the repository at this point in the history
  • Loading branch information
varunagrawal authored Mar 7, 2024
2 parents cdcf232 + ff222ec commit 16934a9
Show file tree
Hide file tree
Showing 12 changed files with 135 additions and 60 deletions.
4 changes: 2 additions & 2 deletions DOCS.md
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,7 @@ The python wrapper supports keyword arguments for functions/methods. Hence, the
- Only one Method/Constructor per line, though methods/constructors can extend across multiple lines.

- Methods can return
- Eigen types: `Matrix`, `Vector`.
- Eigen types: `gtsam::Matrix`, `gtsam::Vector`.
- C/C++ basic types: `string`, `bool`, `size_t`, `int`, `double`, `char`, `unsigned char`.
- `void`
- Any class with which be copied with `std::make_shared()`.
Expand All @@ -34,7 +34,7 @@ The python wrapper supports keyword arguments for functions/methods. Hence, the
- Overloads are supported, but arguments of different types *have* to have different names.

- Arguments to functions can be any of
- Eigen types: `Matrix`, `Vector`.
- Eigen types: `gtsam::Matrix`, `gtsam::Vector`.
- Eigen types and classes as an optionally const reference.
- C/C++ basic types: `string`, `bool`, `size_t`, `size_t`, `double`, `char`, `unsigned char`.
- Any class with which be copied with `std::make_shared()` (except Eigen).
Expand Down
18 changes: 4 additions & 14 deletions gtwrap/interface_parser/type.py
Original file line number Diff line number Diff line change
Expand Up @@ -63,9 +63,6 @@ def __init__(self,
else:
self.instantiations = []

if self.name in ["Matrix", "Vector"] and not self.namespaces:
self.namespaces = ["gtsam"]

@staticmethod
def from_parse_result(parse_result: Union[str, list]):
"""Unpack the parsed result to get the Typename instance."""
Expand Down Expand Up @@ -220,25 +217,21 @@ def to_cpp(self) -> str:
Generate the C++ code for wrapping.
Treat all pointers as "const shared_ptr<T>&"
Treat Matrix and Vector as "const Matrix&" and "const Vector&" resp.
"""

if self.is_shared_ptr:
typename = "std::shared_ptr<{typename}>".format(
typename=self.typename.to_cpp())
elif self.is_ptr:
typename = "{typename}*".format(typename=self.typename.to_cpp())
elif self.is_ref or self.typename.name in ["Matrix", "Vector"]:
elif self.is_ref:
typename = typename = "{typename}&".format(
typename=self.typename.to_cpp())
else:
typename = self.typename.to_cpp()

return ("{const}{typename}".format(
const="const " if
(self.is_const
or self.typename.name in ["Matrix", "Vector"]) else "",
typename=typename))
const="const " if self.is_const else "", typename=typename))

def get_typename(self):
"""Convenience method to get the typename of this type."""
Expand Down Expand Up @@ -305,13 +298,10 @@ def to_cpp(self):
typename = f"std::shared_ptr<{typename}>"
elif self.is_ptr:
typename = "{typename}*".format(typename=typename)
elif self.is_ref or self.typename.name in ["Matrix", "Vector"]:
elif self.is_ref:
typename = typename = "{typename}&".format(typename=typename)
else:
pass

return ("{const}{typename}".format(
const="const " if
(self.is_const
or self.typename.name in ["Matrix", "Vector"]) else "",
typename=typename))
const="const " if self.is_const else "", typename=typename))
12 changes: 6 additions & 6 deletions tests/expected/matlab/MyFactorPosePoint2.m
Original file line number Diff line number Diff line change
Expand Up @@ -15,17 +15,17 @@
function obj = MyFactorPosePoint2(varargin)
if nargin == 2 && isa(varargin{1}, 'uint64') && varargin{1} == uint64(5139824614673773682)
my_ptr = varargin{2};
class_wrapper(76, my_ptr);
class_wrapper(80, my_ptr);
elseif nargin == 4 && isa(varargin{1},'numeric') && isa(varargin{2},'numeric') && isa(varargin{3},'double') && isa(varargin{4},'gtsam.noiseModel.Base')
my_ptr = class_wrapper(77, varargin{1}, varargin{2}, varargin{3}, varargin{4});
my_ptr = class_wrapper(81, varargin{1}, varargin{2}, varargin{3}, varargin{4});
else
error('Arguments do not match any overload of MyFactorPosePoint2 constructor');
end
obj.ptr_MyFactorPosePoint2 = my_ptr;
end

function delete(obj)
class_wrapper(78, obj.ptr_MyFactorPosePoint2);
class_wrapper(82, obj.ptr_MyFactorPosePoint2);
end

function display(obj), obj.print(''); end
Expand All @@ -36,19 +36,19 @@ function delete(obj)
% PRINT usage: print(string s, KeyFormatter keyFormatter) : returns void
% Doxygen can be found at https://gtsam.org/doxygen/
if length(varargin) == 2 && isa(varargin{1},'char') && isa(varargin{2},'gtsam.KeyFormatter')
class_wrapper(79, this, varargin{:});
class_wrapper(83, this, varargin{:});
return
end
% PRINT usage: print(string s) : returns void
% Doxygen can be found at https://gtsam.org/doxygen/
if length(varargin) == 1 && isa(varargin{1},'char')
class_wrapper(80, this, varargin{:});
class_wrapper(84, this, varargin{:});
return
end
% PRINT usage: print() : returns void
% Doxygen can be found at https://gtsam.org/doxygen/
if length(varargin) == 0
class_wrapper(81, this, varargin{:});
class_wrapper(85, this, varargin{:});
return
end
error('Arguments do not match any overload of function MyFactorPosePoint2.print');
Expand Down
99 changes: 87 additions & 12 deletions tests/expected/matlab/class_wrapper.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -33,6 +33,8 @@ typedef std::set<std::shared_ptr<TemplatedConstructor>*> Collector_TemplatedCons
static Collector_TemplatedConstructor collector_TemplatedConstructor;
typedef std::set<std::shared_ptr<FastSet>*> Collector_FastSet;
static Collector_FastSet collector_FastSet;
typedef std::set<std::shared_ptr<HessianFactor>*> Collector_HessianFactor;
static Collector_HessianFactor collector_HessianFactor;
typedef std::set<std::shared_ptr<MyFactorPosePoint2>*> Collector_MyFactorPosePoint2;
static Collector_MyFactorPosePoint2 collector_MyFactorPosePoint2;

Expand Down Expand Up @@ -109,6 +111,12 @@ void _deleteAllObjects()
collector_FastSet.erase(iter++);
anyDeleted = true;
} }
{ for(Collector_HessianFactor::iterator iter = collector_HessianFactor.begin();
iter != collector_HessianFactor.end(); ) {
delete *iter;
collector_HessianFactor.erase(iter++);
anyDeleted = true;
} }
{ for(Collector_MyFactorPosePoint2::iterator iter = collector_MyFactorPosePoint2.begin();
iter != collector_MyFactorPosePoint2.end(); ) {
delete *iter;
Expand All @@ -129,6 +137,7 @@ void _class_RTTIRegister() {
if(!alreadyCreated) {
std::map<std::string, std::string> types;

types.insert(std::make_pair(typeid(HessianFactor).name(), "HessianFactor"));


mxArray *registry = mexGetVariable("global", "gtsamwrap_rttiRegistry");
Expand Down Expand Up @@ -885,7 +894,61 @@ void FastSet_deconstructor_75(int nargout, mxArray *out[], int nargin, const mxA
delete self;
}

void MyFactorPosePoint2_collectorInsertAndMakeBase_76(int nargout, mxArray *out[], int nargin, const mxArray *in[])
void HessianFactor_collectorInsertAndMakeBase_76(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
mexAtExit(&_deleteAllObjects);
typedef std::shared_ptr<HessianFactor> Shared;

Shared *self = *reinterpret_cast<Shared**> (mxGetData(in[0]));
collector_HessianFactor.insert(self);

typedef std::shared_ptr<gtsam::GaussianFactor> SharedBase;
out[0] = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL);
*reinterpret_cast<SharedBase**>(mxGetData(out[0])) = new SharedBase(*self);
}

void HessianFactor_upcastFromVoid_77(int nargout, mxArray *out[], int nargin, const mxArray *in[]) {
mexAtExit(&_deleteAllObjects);
typedef std::shared_ptr<HessianFactor> Shared;
std::shared_ptr<void> *asVoid = *reinterpret_cast<std::shared_ptr<void>**> (mxGetData(in[0]));
out[0] = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL);
Shared *self = new Shared(std::static_pointer_cast<HessianFactor>(*asVoid));
*reinterpret_cast<Shared**>(mxGetData(out[0])) = self;
}

void HessianFactor_constructor_78(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
mexAtExit(&_deleteAllObjects);
typedef std::shared_ptr<HessianFactor> Shared;

gtsam::KeyVector& js = *unwrap_shared_ptr< gtsam::KeyVector >(in[0], "ptr_gtsamKeyVector");
std::vector<Matrix>& Gs = *unwrap_shared_ptr< std::vector<Matrix> >(in[1], "ptr_stdvectorMatrix");
std::vector<Vector>& gs = *unwrap_shared_ptr< std::vector<Vector> >(in[2], "ptr_stdvectorVector");
double f = unwrap< double >(in[3]);
Shared *self = new Shared(new HessianFactor(js,Gs,gs,f));
collector_HessianFactor.insert(self);
out[0] = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL);
*reinterpret_cast<Shared**> (mxGetData(out[0])) = self;

typedef std::shared_ptr<gtsam::GaussianFactor> SharedBase;
out[1] = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL);
*reinterpret_cast<SharedBase**>(mxGetData(out[1])) = new SharedBase(*self);
}

void HessianFactor_deconstructor_79(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
typedef std::shared_ptr<HessianFactor> Shared;
checkArguments("delete_HessianFactor",nargout,nargin,1);
Shared *self = *reinterpret_cast<Shared**>(mxGetData(in[0]));
Collector_HessianFactor::iterator item;
item = collector_HessianFactor.find(self);
if(item != collector_HessianFactor.end()) {
collector_HessianFactor.erase(item);
}
delete self;
}

void MyFactorPosePoint2_collectorInsertAndMakeBase_80(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
mexAtExit(&_deleteAllObjects);
typedef std::shared_ptr<MyFactor<gtsam::Pose2, gtsam::Matrix>> Shared;
Expand All @@ -894,7 +957,7 @@ void MyFactorPosePoint2_collectorInsertAndMakeBase_76(int nargout, mxArray *out[
collector_MyFactorPosePoint2.insert(self);
}

void MyFactorPosePoint2_constructor_77(int nargout, mxArray *out[], int nargin, const mxArray *in[])
void MyFactorPosePoint2_constructor_81(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
mexAtExit(&_deleteAllObjects);
typedef std::shared_ptr<MyFactor<gtsam::Pose2, gtsam::Matrix>> Shared;
Expand All @@ -909,7 +972,7 @@ void MyFactorPosePoint2_constructor_77(int nargout, mxArray *out[], int nargin,
*reinterpret_cast<Shared**> (mxGetData(out[0])) = self;
}

void MyFactorPosePoint2_deconstructor_78(int nargout, mxArray *out[], int nargin, const mxArray *in[])
void MyFactorPosePoint2_deconstructor_82(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
typedef std::shared_ptr<MyFactor<gtsam::Pose2, gtsam::Matrix>> Shared;
checkArguments("delete_MyFactorPosePoint2",nargout,nargin,1);
Expand All @@ -922,7 +985,7 @@ void MyFactorPosePoint2_deconstructor_78(int nargout, mxArray *out[], int nargin
delete self;
}

void MyFactorPosePoint2_print_79(int nargout, mxArray *out[], int nargin, const mxArray *in[])
void MyFactorPosePoint2_print_83(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
checkArguments("print",nargout,nargin-1,2);
auto obj = unwrap_shared_ptr<MyFactor<gtsam::Pose2, gtsam::Matrix>>(in[0], "ptr_MyFactorPosePoint2");
Expand All @@ -931,15 +994,15 @@ void MyFactorPosePoint2_print_79(int nargout, mxArray *out[], int nargin, const
obj->print(s,keyFormatter);
}

void MyFactorPosePoint2_print_80(int nargout, mxArray *out[], int nargin, const mxArray *in[])
void MyFactorPosePoint2_print_84(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
checkArguments("print",nargout,nargin-1,1);
auto obj = unwrap_shared_ptr<MyFactor<gtsam::Pose2, gtsam::Matrix>>(in[0], "ptr_MyFactorPosePoint2");
string& s = *unwrap_shared_ptr< string >(in[1], "ptr_string");
obj->print(s,gtsam::DefaultKeyFormatter);
}

void MyFactorPosePoint2_print_81(int nargout, mxArray *out[], int nargin, const mxArray *in[])
void MyFactorPosePoint2_print_85(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
checkArguments("print",nargout,nargin-1,0);
auto obj = unwrap_shared_ptr<MyFactor<gtsam::Pose2, gtsam::Matrix>>(in[0], "ptr_MyFactorPosePoint2");
Expand Down Expand Up @@ -1187,22 +1250,34 @@ void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[])
FastSet_deconstructor_75(nargout, out, nargin-1, in+1);
break;
case 76:
MyFactorPosePoint2_collectorInsertAndMakeBase_76(nargout, out, nargin-1, in+1);
HessianFactor_collectorInsertAndMakeBase_76(nargout, out, nargin-1, in+1);
break;
case 77:
MyFactorPosePoint2_constructor_77(nargout, out, nargin-1, in+1);
HessianFactor_upcastFromVoid_77(nargout, out, nargin-1, in+1);
break;
case 78:
MyFactorPosePoint2_deconstructor_78(nargout, out, nargin-1, in+1);
HessianFactor_constructor_78(nargout, out, nargin-1, in+1);
break;
case 79:
MyFactorPosePoint2_print_79(nargout, out, nargin-1, in+1);
HessianFactor_deconstructor_79(nargout, out, nargin-1, in+1);
break;
case 80:
MyFactorPosePoint2_print_80(nargout, out, nargin-1, in+1);
MyFactorPosePoint2_collectorInsertAndMakeBase_80(nargout, out, nargin-1, in+1);
break;
case 81:
MyFactorPosePoint2_print_81(nargout, out, nargin-1, in+1);
MyFactorPosePoint2_constructor_81(nargout, out, nargin-1, in+1);
break;
case 82:
MyFactorPosePoint2_deconstructor_82(nargout, out, nargin-1, in+1);
break;
case 83:
MyFactorPosePoint2_print_83(nargout, out, nargin-1, in+1);
break;
case 84:
MyFactorPosePoint2_print_84(nargout, out, nargin-1, in+1);
break;
case 85:
MyFactorPosePoint2_print_85(nargout, out, nargin-1, in+1);
break;
}
} catch(const std::exception& e) {
Expand Down
3 changes: 3 additions & 0 deletions tests/expected/python/class_pybind.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -97,6 +97,9 @@ PYBIND11_MODULE(class_py, m_) {
.def("__contains__",[](FastSet* self, size_t key){return std::find(self->begin(), self->end(), key) != self->end();}, py::arg("key"))
.def("__iter__",[](FastSet* self){return py::make_iterator(self->begin(), self->end());});

py::class_<HessianFactor, gtsam::GaussianFactor, std::shared_ptr<HessianFactor>>(m_, "HessianFactor")
.def(py::init<const gtsam::KeyVector&, const std::vector<gtsam::Matrix>&, const std::vector<gtsam::Vector>&, double>(), py::arg("js"), py::arg("Gs"), py::arg("gs"), py::arg("f"));

py::class_<MyFactor<gtsam::Pose2, gtsam::Matrix>, std::shared_ptr<MyFactor<gtsam::Pose2, gtsam::Matrix>>>(m_, "MyFactorPosePoint2")
.def(py::init<size_t, size_t, double, const std::shared_ptr<gtsam::noiseModel::Base>>(), py::arg("key1"), py::arg("key2"), py::arg("measured"), py::arg("noiseModel"))
.def("print",[](MyFactor<gtsam::Pose2, gtsam::Matrix>* self, const string& s, const gtsam::KeyFormatter& keyFormatter){ py::scoped_ostream_redirect output; self->print(s, keyFormatter);}, py::arg("s") = "factor: ", py::arg("keyFormatter") = gtsam::DefaultKeyFormatter)
Expand Down
8 changes: 4 additions & 4 deletions tests/expected/python/inheritance_pybind.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -40,12 +40,12 @@ PYBIND11_MODULE(inheritance_py, m_) {
.def("templatedMethodVector",[](MyTemplate<gtsam::Matrix>* self, const gtsam::Vector& t){return self->templatedMethod<gtsam::Vector>(t);}, py::arg("t"))
.def("templatedMethodMatrix",[](MyTemplate<gtsam::Matrix>* self, const gtsam::Matrix& t){return self->templatedMethod<gtsam::Matrix>(t);}, py::arg("t"))
.def("accept_T",[](MyTemplate<gtsam::Matrix>* self, const gtsam::Matrix& value){ self->accept_T(value);}, py::arg("value"))
.def("accept_Tptr",[](MyTemplate<gtsam::Matrix>* self, const std::shared_ptr<gtsam::Matrix> value){ self->accept_Tptr(value);}, py::arg("value"))
.def("return_Tptr",[](MyTemplate<gtsam::Matrix>* self, const std::shared_ptr<gtsam::Matrix> value){return self->return_Tptr(value);}, py::arg("value"))
.def("return_T",[](MyTemplate<gtsam::Matrix>* self, const gtsam::Matrix* value){return self->return_T(value);}, py::arg("value"))
.def("accept_Tptr",[](MyTemplate<gtsam::Matrix>* self, std::shared_ptr<gtsam::Matrix> value){ self->accept_Tptr(value);}, py::arg("value"))
.def("return_Tptr",[](MyTemplate<gtsam::Matrix>* self, std::shared_ptr<gtsam::Matrix> value){return self->return_Tptr(value);}, py::arg("value"))
.def("return_T",[](MyTemplate<gtsam::Matrix>* self, gtsam::Matrix* value){return self->return_T(value);}, py::arg("value"))
.def("create_ptrs",[](MyTemplate<gtsam::Matrix>* self){return self->create_ptrs();})
.def("create_MixedPtrs",[](MyTemplate<gtsam::Matrix>* self){return self->create_MixedPtrs();})
.def("return_ptrs",[](MyTemplate<gtsam::Matrix>* self, const std::shared_ptr<gtsam::Matrix> p1, const std::shared_ptr<gtsam::Matrix> p2){return self->return_ptrs(p1, p2);}, py::arg("p1"), py::arg("p2"))
.def("return_ptrs",[](MyTemplate<gtsam::Matrix>* self, std::shared_ptr<gtsam::Matrix> p1, std::shared_ptr<gtsam::Matrix> p2){return self->return_ptrs(p1, p2);}, py::arg("p1"), py::arg("p2"))
.def_static("Level",[](const gtsam::Matrix& K){return MyTemplate<gtsam::Matrix>::Level(K);}, py::arg("K"));

py::class_<MyTemplate<A>, MyBase, std::shared_ptr<MyTemplate<A>>>(m_, "MyTemplateA")
Expand Down
27 changes: 17 additions & 10 deletions tests/fixtures/class.i
Original file line number Diff line number Diff line change
Expand Up @@ -41,26 +41,27 @@ class Test {
double value;
string name;

pair<Vector,Matrix> return_pair (Vector v, Matrix A) const; // intentionally the first method
pair<Vector,Matrix> return_pair (Vector v) const; // overload
// intentionally the first method
pair<gtsam::Vector,gtsam::Matrix> return_pair (const gtsam::Vector& v, const gtsam::Matrix& A) const;
pair<gtsam::Vector,gtsam::Matrix> return_pair (const gtsam::Vector& v) const; // overload

bool return_bool (bool value) const; // comment after a line!
size_t return_size_t (size_t value) const;
int return_int (int value) const;
double return_double (double value) const;

Test(double a, Matrix b); // a constructor in the middle of a class
Test(double a, const gtsam::Matrix& b); // a constructor in the middle of a class

// comments in the middle!

// (more) comments in the middle!

string return_string (string value) const;
Vector return_vector1(Vector value) const;
Matrix return_matrix1(Matrix value) const;
Vector return_vector2(Vector value) const;
Matrix return_matrix2(Matrix value) const;
void arg_EigenConstRef(const Matrix& value) const;
gtsam::Vector return_vector1(const gtsam::Vector& value) const;
gtsam::Matrix return_matrix1(const gtsam::Matrix& value) const;
gtsam::Vector return_vector2(const gtsam::Vector& value) const;
gtsam::Matrix return_matrix2(const gtsam::Matrix& value) const;
void arg_EigenConstRef(const gtsam::Matrix& value) const;

bool return_field(const Test& t) const;

Expand Down Expand Up @@ -103,7 +104,7 @@ class MyFactor {
};

// and a typedef specializing it
typedef MyFactor<gtsam::Pose2, Matrix> MyFactorPosePoint2;
typedef MyFactor<gtsam::Pose2, gtsam::Matrix> MyFactorPosePoint2;

template<T = {double}>
class PrimitiveRef {
Expand Down Expand Up @@ -153,4 +154,10 @@ class FastSet {
__len__();
__contains__(size_t key);
__iter__();
};
};

virtual class HessianFactor : gtsam::GaussianFactor {
HessianFactor(const gtsam::KeyVector& js,
const std::vector<gtsam::Matrix>& Gs,
const std::vector<gtsam::Vector>& gs, double f);
};
Loading

0 comments on commit 16934a9

Please sign in to comment.