Merge pull request #739 from borglab/feature/wrapupdate_multipleinterfacefiles

release/4.3a0
Frank Dellaert 2021-04-13 08:14:10 -04:00 committed by GitHub
commit f95cc0b3a4
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
15 changed files with 140 additions and 5 deletions

View File

@ -8,6 +8,8 @@ The interface to the toolbox is generated automatically by the wrap tool which d
The tool generates matlab proxy objects together with all the native functions for wrapping and unwrapping scalar and non scalar types and objects.
The interface generated by the wrap tool also redirects the standard output stream (cout) to matlab's console.
For instructions on updating the version of the [wrap library](https://github.com/borglab/wrap) included in GTSAM to the latest version, please refer to the [wrap README](https://github.com/borglab/wrap/blob/master/README.md#git-subtree-and-contributing)
## Ubuntu
If you have a newer Ubuntu system (later than 10.04), you must make a small modification to your MATLAB installation, due to MATLAB being distributed with an old version of the C++ standard library. Delete or rename all files starting with `libstdc++` in your MATLAB installation directory, in paths:

View File

@ -4,6 +4,8 @@
This is the Python wrapper around the GTSAM C++ library. We use our custom [wrap library](https://github.com/borglab/wrap) to generate the bindings to the underlying C++ code.
For instructions on updating the version of the [wrap library](https://github.com/borglab/wrap) included in GTSAM to the latest version, please refer to the [wrap README](https://github.com/borglab/wrap/blob/master/README.md#git-subtree-and-contributing)
## Requirements
- If you want to build the GTSAM python library for a specific python version (eg 3.6),

View File

@ -13,6 +13,7 @@
#include <pybind11/eigen.h>
#include <pybind11/stl_bind.h>
#include <pybind11/pybind11.h>
#include <pybind11/iostream.h>
#include "gtsam/config.h"
#include "gtsam/base/serialization.h"
#include "gtsam/nonlinear/utilities.h" // for RedirectCout.

View File

@ -13,6 +13,7 @@
#include <pybind11/eigen.h>
#include <pybind11/stl_bind.h>
#include <pybind11/pybind11.h>
#include <pybind11/iostream.h>
#include "gtsam/base/serialization.h"
#include "gtsam/nonlinear/utilities.h" // for RedirectCout.

View File

@ -98,6 +98,7 @@ The python wrapper supports keyword arguments for functions/methods. Hence, the
- Virtual inheritance
- Specify fully-qualified base classes, i.e. `virtual class Derived : ns::Base {` where `ns` is the namespace.
- Mark with `virtual` keyword, e.g. `virtual class Base {`, and also `virtual class Derived : ns::Base {`.
- Base classes can be templated, e.g. `virtual class Dog: ns::Animal<Pet> {};`. This is useful when you want to inherit from specialized classes.
- Forward declarations must also be marked virtual, e.g. `virtual class ns::Base;` and
also `virtual class ns::Derived;`.
- Pure virtual (abstract) classes should list no constructors in the interface file.

View File

@ -103,3 +103,37 @@ macro(gtwrap_get_python_version)
configure_python_variables()
endmacro()
# Concatenate multiple wrapper interface headers into one.
# The concatenation will be (re)performed if and only if any interface files
# change.
#
# Arguments:
# ~~~
# destination: The concatenated master interface header file will be placed here.
# inputs (optional): All the input interface header files
function(combine_interface_headers
destination
#inputs
)
# check if any interface headers changed
foreach(INTERFACE_FILE ${ARGN})
if(NOT EXISTS ${destination} OR
${INTERFACE_FILE} IS_NEWER_THAN ${destination})
set(UPDATE_INTERFACE TRUE)
endif()
# trigger cmake on file change
set_property(DIRECTORY
APPEND
PROPERTY CMAKE_CONFIGURE_DEPENDS ${INTERFACE_FILE})
endforeach()
# if so, then update the overall interface file
if (UPDATE_INTERFACE)
file(WRITE ${destination} "")
# append additional interface headers to end of gtdynamics.i
foreach(INTERFACE_FILE ${ARGN})
file(READ ${INTERFACE_FILE} interface_contents)
file(APPEND ${destination} "${interface_contents}")
endforeach()
endif()
endfunction()

View File

@ -279,7 +279,7 @@ class Class:
elif isinstance(m, Operator):
self.operators.append(m)
_parent = COLON + Typename.rule("parent_class")
_parent = COLON + (TemplatedType.rule ^ Typename.rule)("parent_class")
rule = (
Optional(Template.rule("template")) #
+ Optional(VIRTUAL("is_virtual")) #
@ -319,11 +319,16 @@ class Class:
self.is_virtual = is_virtual
self.name = name
if parent_class:
# If it is in an iterable, extract the parent class.
if isinstance(parent_class, Iterable):
self.parent_class = parent_class[0]
else:
self.parent_class = parent_class
parent_class = parent_class[0]
# If the base class is a TemplatedType,
# we want the instantiated Typename
if isinstance(parent_class, TemplatedType):
parent_class = parent_class.typename
self.parent_class = parent_class
else:
self.parent_class = ''

View File

@ -125,6 +125,11 @@ class PybindWrapper:
))
if method.name == 'print':
# Redirect stdout - see pybind docs for why this is a good idea:
# https://pybind11.readthedocs.io/en/stable/advanced/pycpp/utilities.html#capturing-standard-output-from-ostream
ret = ret.replace('self->', 'py::scoped_ostream_redirect output; self->')
# __repr__() uses print's implementation:
type_list = method.args.to_cpp(self.use_boost)
if len(type_list) > 0 and type_list[0].strip() == 'string':
ret += '''{prefix}.def("__repr__",

View File

@ -50,6 +50,8 @@ typedef std::set<boost::shared_ptr<MyTemplatePoint2>*> Collector_MyTemplatePoint
static Collector_MyTemplatePoint2 collector_MyTemplatePoint2;
typedef std::set<boost::shared_ptr<MyTemplateMatrix>*> Collector_MyTemplateMatrix;
static Collector_MyTemplateMatrix collector_MyTemplateMatrix;
typedef std::set<boost::shared_ptr<ForwardKinematicsFactor>*> Collector_ForwardKinematicsFactor;
static Collector_ForwardKinematicsFactor collector_ForwardKinematicsFactor;
void _deleteAllObjects()
{
@ -141,6 +143,12 @@ void _deleteAllObjects()
collector_MyTemplateMatrix.erase(iter++);
anyDeleted = true;
} }
{ for(Collector_ForwardKinematicsFactor::iterator iter = collector_ForwardKinematicsFactor.begin();
iter != collector_ForwardKinematicsFactor.end(); ) {
delete *iter;
collector_ForwardKinematicsFactor.erase(iter++);
anyDeleted = true;
} }
if(anyDeleted)
cout <<
"WARNING: Wrap modules with variables in the workspace have been reloaded due to\n"
@ -156,6 +164,7 @@ void _inheritance_RTTIRegister() {
types.insert(std::make_pair(typeid(MyBase).name(), "MyBase"));
types.insert(std::make_pair(typeid(MyTemplatePoint2).name(), "MyTemplatePoint2"));
types.insert(std::make_pair(typeid(MyTemplateMatrix).name(), "MyTemplateMatrix"));
types.insert(std::make_pair(typeid(ForwardKinematicsFactor).name(), "ForwardKinematicsFactor"));
mxArray *registry = mexGetVariable("global", "gtsamwrap_rttiRegistry");
if(!registry)
@ -555,6 +564,40 @@ void MyTemplateMatrix_Level_34(int nargout, mxArray *out[], int nargin, const mx
out[0] = wrap_shared_ptr(boost::make_shared<MyTemplate<Matrix>>(MyTemplate<gtsam::Matrix>::Level(K)),"MyTemplateMatrix", false);
}
void Test_set_container_35(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
checkArguments("set_container",nargout,nargin-1,1);
auto obj = unwrap_shared_ptr<Test>(in[0], "ptr_Test");
boost::shared_ptr<std::vector<testing::Test>> container = unwrap_shared_ptr< std::vector<testing::Test> >(in[1], "ptr_stdvectorTest");
obj->set_container(*container);
}
void ForwardKinematicsFactor_collectorInsertAndMakeBase_35(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
mexAtExit(&_deleteAllObjects);
typedef boost::shared_ptr<ForwardKinematicsFactor> Shared;
Shared *self = *reinterpret_cast<Shared**> (mxGetData(in[0]));
collector_ForwardKinematicsFactor.insert(self);
typedef boost::shared_ptr<gtsam::BetweenFactor<gtsam::Pose3>> SharedBase;
out[0] = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL);
*reinterpret_cast<SharedBase**>(mxGetData(out[0])) = new SharedBase(*self);
}
void ForwardKinematicsFactor_deconstructor_37(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
typedef boost::shared_ptr<ForwardKinematicsFactor> Shared;
checkArguments("delete_ForwardKinematicsFactor",nargout,nargin,1);
Shared *self = *reinterpret_cast<Shared**>(mxGetData(in[0]));
Collector_ForwardKinematicsFactor::iterator item;
item = collector_ForwardKinematicsFactor.find(self);
if(item != collector_ForwardKinematicsFactor.end()) {
delete self;
collector_ForwardKinematicsFactor.erase(item);
}
}
void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
@ -672,6 +715,15 @@ void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[])
case 34:
MyTemplateMatrix_Level_34(nargout, out, nargin-1, in+1);
break;
case 35:
Test_set_container_35(nargout, out, nargin-1, in+1);
break;
case 36:
ForwardKinematicsFactor_collectorInsertAndMakeBase_35(nargout, out, nargin-1, in+1);
break;
case 37:
ForwardKinematicsFactor_deconstructor_37(nargout, out, nargin-1, in+1);
break;
}
} catch(const std::exception& e) {
mexErrMsgTxt(("Exception from gtsam:\n" + std::string(e.what()) + "\n").c_str());

View File

@ -55,6 +55,8 @@ typedef std::set<boost::shared_ptr<MyTemplatePoint2>*> Collector_MyTemplatePoint
static Collector_MyTemplatePoint2 collector_MyTemplatePoint2;
typedef std::set<boost::shared_ptr<MyTemplateMatrix>*> Collector_MyTemplateMatrix;
static Collector_MyTemplateMatrix collector_MyTemplateMatrix;
typedef std::set<boost::shared_ptr<ForwardKinematicsFactor>*> Collector_ForwardKinematicsFactor;
static Collector_ForwardKinematicsFactor collector_ForwardKinematicsFactor;
typedef std::set<boost::shared_ptr<ns1::ClassA>*> Collector_ns1ClassA;
static Collector_ns1ClassA collector_ns1ClassA;
typedef std::set<boost::shared_ptr<ns1::ClassB>*> Collector_ns1ClassB;
@ -158,6 +160,12 @@ void _deleteAllObjects()
collector_MyTemplateMatrix.erase(iter++);
anyDeleted = true;
} }
{ for(Collector_ForwardKinematicsFactor::iterator iter = collector_ForwardKinematicsFactor.begin();
iter != collector_ForwardKinematicsFactor.end(); ) {
delete *iter;
collector_ForwardKinematicsFactor.erase(iter++);
anyDeleted = true;
} }
{ for(Collector_ns1ClassA::iterator iter = collector_ns1ClassA.begin();
iter != collector_ns1ClassA.end(); ) {
delete *iter;
@ -209,6 +217,7 @@ void _namespaces_RTTIRegister() {
types.insert(std::make_pair(typeid(MyBase).name(), "MyBase"));
types.insert(std::make_pair(typeid(MyTemplatePoint2).name(), "MyTemplatePoint2"));
types.insert(std::make_pair(typeid(MyTemplateMatrix).name(), "MyTemplateMatrix"));
types.insert(std::make_pair(typeid(ForwardKinematicsFactor).name(), "ForwardKinematicsFactor"));
mxArray *registry = mexGetVariable("global", "gtsamwrap_rttiRegistry");
if(!registry)

View File

@ -58,6 +58,8 @@ typedef std::set<boost::shared_ptr<MyTemplatePoint2>*> Collector_MyTemplatePoint
static Collector_MyTemplatePoint2 collector_MyTemplatePoint2;
typedef std::set<boost::shared_ptr<MyTemplateMatrix>*> Collector_MyTemplateMatrix;
static Collector_MyTemplateMatrix collector_MyTemplateMatrix;
typedef std::set<boost::shared_ptr<ForwardKinematicsFactor>*> Collector_ForwardKinematicsFactor;
static Collector_ForwardKinematicsFactor collector_ForwardKinematicsFactor;
typedef std::set<boost::shared_ptr<ns1::ClassA>*> Collector_ns1ClassA;
static Collector_ns1ClassA collector_ns1ClassA;
typedef std::set<boost::shared_ptr<ns1::ClassB>*> Collector_ns1ClassB;
@ -169,6 +171,12 @@ void _deleteAllObjects()
collector_MyTemplateMatrix.erase(iter++);
anyDeleted = true;
} }
{ for(Collector_ForwardKinematicsFactor::iterator iter = collector_ForwardKinematicsFactor.begin();
iter != collector_ForwardKinematicsFactor.end(); ) {
delete *iter;
collector_ForwardKinematicsFactor.erase(iter++);
anyDeleted = true;
} }
{ for(Collector_ns1ClassA::iterator iter = collector_ns1ClassA.begin();
iter != collector_ns1ClassA.end(); ) {
delete *iter;
@ -244,6 +252,7 @@ void _special_cases_RTTIRegister() {
types.insert(std::make_pair(typeid(MyBase).name(), "MyBase"));
types.insert(std::make_pair(typeid(MyTemplatePoint2).name(), "MyTemplatePoint2"));
types.insert(std::make_pair(typeid(MyTemplateMatrix).name(), "MyTemplateMatrix"));
types.insert(std::make_pair(typeid(ForwardKinematicsFactor).name(), "ForwardKinematicsFactor"));
mxArray *registry = mexGetVariable("global", "gtsamwrap_rttiRegistry");
if(!registry)

View File

@ -55,7 +55,7 @@ PYBIND11_MODULE(class_py, m_) {
.def("create_ptrs",[](Test* self){return self->create_ptrs();})
.def("create_MixedPtrs",[](Test* self){return self->create_MixedPtrs();})
.def("return_ptrs",[](Test* self, std::shared_ptr<Test> p1, std::shared_ptr<Test> p2){return self->return_ptrs(p1, p2);}, py::arg("p1"), py::arg("p2"))
.def("print_",[](Test* self){ self->print();})
.def("print_",[](Test* self){ py::scoped_ostream_redirect output; self->print();})
.def("__repr__",
[](const Test &a) {
gtsam::RedirectCout redirect;

View File

@ -54,6 +54,8 @@ PYBIND11_MODULE(inheritance_py, m_) {
.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_static("Level",[](const gtsam::Matrix& K){return MyTemplate<gtsam::Matrix>::Level(K);}, py::arg("K"));
py::class_<ForwardKinematicsFactor, gtsam::BetweenFactor<gtsam::Pose3>, std::shared_ptr<ForwardKinematicsFactor>>(m_, "ForwardKinematicsFactor");
#include "python/specializations.h"

View File

@ -22,3 +22,6 @@ virtual class MyTemplate : MyBase {
static This Level(const T& K);
};
virtual class ForwardKinematicsFactor : gtsam::BetweenFactor<gtsam::Pose3> {};

View File

@ -388,6 +388,15 @@ class TestInterfaceParser(unittest.TestCase):
ret.parent_class.namespaces)
self.assertTrue(ret.is_virtual)
ret = Class.rule.parseString(
"class ForwardKinematicsFactor : gtsam::BetweenFactor<gtsam::Pose3> {};"
)[0]
self.assertEqual("ForwardKinematicsFactor", ret.name)
self.assertEqual("BetweenFactor", ret.parent_class.name)
self.assertEqual(["gtsam"], ret.parent_class.namespaces)
self.assertEqual("Pose3", ret.parent_class.instantiations[0].name)
self.assertEqual(["gtsam"], ret.parent_class.instantiations[0].namespaces)
def test_include(self):
"""Test for include statements."""
include = Include.rule.parseString(