Merging 'master' into 'wrap'
commit
5057d81dfa
|
@ -119,24 +119,27 @@ class Constructor:
|
||||||
Can have 0 or more arguments.
|
Can have 0 or more arguments.
|
||||||
"""
|
"""
|
||||||
rule = (
|
rule = (
|
||||||
IDENT("name") #
|
Optional(Template.rule("template")) #
|
||||||
|
+ IDENT("name") #
|
||||||
+ LPAREN #
|
+ LPAREN #
|
||||||
+ ArgumentList.rule("args_list") #
|
+ ArgumentList.rule("args_list") #
|
||||||
+ RPAREN #
|
+ RPAREN #
|
||||||
+ SEMI_COLON # BR
|
+ SEMI_COLON # BR
|
||||||
).setParseAction(lambda t: Constructor(t.name, t.args_list))
|
).setParseAction(lambda t: Constructor(t.name, t.args_list, t.template))
|
||||||
|
|
||||||
def __init__(self,
|
def __init__(self,
|
||||||
name: str,
|
name: str,
|
||||||
args: ArgumentList,
|
args: ArgumentList,
|
||||||
|
template: Union[Template, Any],
|
||||||
parent: Union["Class", Any] = ''):
|
parent: Union["Class", Any] = ''):
|
||||||
self.name = name
|
self.name = name
|
||||||
self.args = args
|
self.args = args
|
||||||
|
self.template = template
|
||||||
|
|
||||||
self.parent = parent
|
self.parent = parent
|
||||||
|
|
||||||
def __repr__(self) -> str:
|
def __repr__(self) -> str:
|
||||||
return "Constructor: {}".format(self.name)
|
return "Constructor: {}{}".format(self.name, self.args)
|
||||||
|
|
||||||
|
|
||||||
class Operator:
|
class Operator:
|
||||||
|
@ -260,17 +263,9 @@ class Class:
|
||||||
+ RBRACE #
|
+ RBRACE #
|
||||||
+ SEMI_COLON # BR
|
+ SEMI_COLON # BR
|
||||||
).setParseAction(lambda t: Class(
|
).setParseAction(lambda t: Class(
|
||||||
t.template,
|
t.template, t.is_virtual, t.name, t.parent_class, t.members.ctors, t.
|
||||||
t.is_virtual,
|
members.methods, t.members.static_methods, t.members.properties, t.
|
||||||
t.name,
|
members.operators, t.members.enums))
|
||||||
t.parent_class,
|
|
||||||
t.members.ctors,
|
|
||||||
t.members.methods,
|
|
||||||
t.members.static_methods,
|
|
||||||
t.members.properties,
|
|
||||||
t.members.operators,
|
|
||||||
t.members.enums
|
|
||||||
))
|
|
||||||
|
|
||||||
def __init__(
|
def __init__(
|
||||||
self,
|
self,
|
||||||
|
|
|
@ -81,7 +81,7 @@ class ArgumentList:
|
||||||
return ArgumentList([])
|
return ArgumentList([])
|
||||||
|
|
||||||
def __repr__(self) -> str:
|
def __repr__(self) -> str:
|
||||||
return self.args_list.__repr__()
|
return repr(tuple(self.args_list))
|
||||||
|
|
||||||
def __len__(self) -> int:
|
def __len__(self) -> int:
|
||||||
return len(self.args_list)
|
return len(self.args_list)
|
||||||
|
|
|
@ -41,6 +41,8 @@ def instantiate_type(ctype: parser.Type,
|
||||||
|
|
||||||
str_arg_typename = str(ctype.typename)
|
str_arg_typename = str(ctype.typename)
|
||||||
|
|
||||||
|
# Instantiate templates which have enumerated instantiations in the template.
|
||||||
|
# E.g. `template<T={double}>`.
|
||||||
if str_arg_typename in template_typenames:
|
if str_arg_typename in template_typenames:
|
||||||
idx = template_typenames.index(str_arg_typename)
|
idx = template_typenames.index(str_arg_typename)
|
||||||
return parser.Type(
|
return parser.Type(
|
||||||
|
@ -51,14 +53,15 @@ def instantiate_type(ctype: parser.Type,
|
||||||
is_ref=ctype.is_ref,
|
is_ref=ctype.is_ref,
|
||||||
is_basic=ctype.is_basic,
|
is_basic=ctype.is_basic,
|
||||||
)
|
)
|
||||||
|
|
||||||
|
# If a method has the keyword `This`, we replace it with the (instantiated) class.
|
||||||
elif str_arg_typename == 'This':
|
elif str_arg_typename == 'This':
|
||||||
|
# Check if the class is template instantiated
|
||||||
|
# so we can replace it with the instantiated version.
|
||||||
if instantiated_class:
|
if instantiated_class:
|
||||||
name = instantiated_class.original.name
|
name = instantiated_class.original.name
|
||||||
namespaces_name = instantiated_class.namespaces()
|
namespaces_name = instantiated_class.namespaces()
|
||||||
namespaces_name.append(name)
|
namespaces_name.append(name)
|
||||||
# print("INST: {}, {}, CPP: {}, CLS: {}".format(
|
|
||||||
# ctype, instantiations, cpp_typename, instantiated_class.instantiations
|
|
||||||
# ), file=sys.stderr)
|
|
||||||
cpp_typename = parser.Typename(
|
cpp_typename = parser.Typename(
|
||||||
namespaces_name,
|
namespaces_name,
|
||||||
instantiations=instantiated_class.instantiations)
|
instantiations=instantiated_class.instantiations)
|
||||||
|
@ -71,6 +74,14 @@ def instantiate_type(ctype: parser.Type,
|
||||||
is_ref=ctype.is_ref,
|
is_ref=ctype.is_ref,
|
||||||
is_basic=ctype.is_basic,
|
is_basic=ctype.is_basic,
|
||||||
)
|
)
|
||||||
|
|
||||||
|
# Case when 'This' is present in the type namespace, e.g `This::Subclass`.
|
||||||
|
elif 'This' in str_arg_typename:
|
||||||
|
# Simply get the index of `This` in the namespace and replace it with the instantiated name.
|
||||||
|
namespace_idx = ctype.typename.namespaces.index('This')
|
||||||
|
ctype.typename.namespaces[namespace_idx] = cpp_typename.name
|
||||||
|
return ctype
|
||||||
|
|
||||||
else:
|
else:
|
||||||
return ctype
|
return ctype
|
||||||
|
|
||||||
|
@ -368,19 +379,45 @@ class InstantiatedClass(parser.Class):
|
||||||
"""
|
"""
|
||||||
instantiated_ctors = []
|
instantiated_ctors = []
|
||||||
|
|
||||||
for ctor in self.original.ctors:
|
def instantiate(instantiated_ctors, ctor, typenames, instantiations):
|
||||||
instantiated_args = instantiate_args_list(
|
instantiated_args = instantiate_args_list(
|
||||||
ctor.args.list(),
|
ctor.args.list(),
|
||||||
typenames,
|
typenames,
|
||||||
self.instantiations,
|
instantiations,
|
||||||
self.cpp_typename(),
|
self.cpp_typename(),
|
||||||
)
|
)
|
||||||
instantiated_ctors.append(
|
instantiated_ctors.append(
|
||||||
parser.Constructor(
|
parser.Constructor(
|
||||||
name=self.name,
|
name=self.name,
|
||||||
args=parser.ArgumentList(instantiated_args),
|
args=parser.ArgumentList(instantiated_args),
|
||||||
|
template=self.original.template,
|
||||||
parent=self,
|
parent=self,
|
||||||
))
|
))
|
||||||
|
return instantiated_ctors
|
||||||
|
|
||||||
|
for ctor in self.original.ctors:
|
||||||
|
# Add constructor templates to the typenames and instantiations
|
||||||
|
if isinstance(ctor.template, parser.template.Template):
|
||||||
|
typenames.extend(ctor.template.typenames)
|
||||||
|
|
||||||
|
# Get all combinations of template args
|
||||||
|
for instantiations in itertools.product(
|
||||||
|
*ctor.template.instantiations):
|
||||||
|
instantiations = self.instantiations + list(instantiations)
|
||||||
|
|
||||||
|
instantiated_ctors = instantiate(
|
||||||
|
instantiated_ctors,
|
||||||
|
ctor,
|
||||||
|
typenames=typenames,
|
||||||
|
instantiations=instantiations)
|
||||||
|
|
||||||
|
else:
|
||||||
|
# If no constructor level templates, just use the class templates
|
||||||
|
instantiated_ctors = instantiate(
|
||||||
|
instantiated_ctors,
|
||||||
|
ctor,
|
||||||
|
typenames=typenames,
|
||||||
|
instantiations=self.instantiations)
|
||||||
return instantiated_ctors
|
return instantiated_ctors
|
||||||
|
|
||||||
def instantiate_static_methods(self, typenames):
|
def instantiate_static_methods(self, typenames):
|
||||||
|
|
|
@ -15,9 +15,9 @@ classdef MyFactorPosePoint2 < handle
|
||||||
function obj = MyFactorPosePoint2(varargin)
|
function obj = MyFactorPosePoint2(varargin)
|
||||||
if nargin == 2 && isa(varargin{1}, 'uint64') && varargin{1} == uint64(5139824614673773682)
|
if nargin == 2 && isa(varargin{1}, 'uint64') && varargin{1} == uint64(5139824614673773682)
|
||||||
my_ptr = varargin{2};
|
my_ptr = varargin{2};
|
||||||
class_wrapper(56, my_ptr);
|
class_wrapper(62, my_ptr);
|
||||||
elseif nargin == 4 && isa(varargin{1},'numeric') && isa(varargin{2},'numeric') && isa(varargin{3},'double') && isa(varargin{4},'gtsam.noiseModel.Base')
|
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(57, varargin{1}, varargin{2}, varargin{3}, varargin{4});
|
my_ptr = class_wrapper(63, varargin{1}, varargin{2}, varargin{3}, varargin{4});
|
||||||
else
|
else
|
||||||
error('Arguments do not match any overload of MyFactorPosePoint2 constructor');
|
error('Arguments do not match any overload of MyFactorPosePoint2 constructor');
|
||||||
end
|
end
|
||||||
|
@ -25,7 +25,7 @@ classdef MyFactorPosePoint2 < handle
|
||||||
end
|
end
|
||||||
|
|
||||||
function delete(obj)
|
function delete(obj)
|
||||||
class_wrapper(58, obj.ptr_MyFactorPosePoint2);
|
class_wrapper(64, obj.ptr_MyFactorPosePoint2);
|
||||||
end
|
end
|
||||||
|
|
||||||
function display(obj), obj.print(''); end
|
function display(obj), obj.print(''); end
|
||||||
|
@ -36,7 +36,7 @@ classdef MyFactorPosePoint2 < handle
|
||||||
% PRINT usage: print(string s, KeyFormatter keyFormatter) : returns void
|
% PRINT usage: print(string s, KeyFormatter keyFormatter) : returns void
|
||||||
% Doxygen can be found at https://gtsam.org/doxygen/
|
% Doxygen can be found at https://gtsam.org/doxygen/
|
||||||
if length(varargin) == 2 && isa(varargin{1},'char') && isa(varargin{2},'gtsam.KeyFormatter')
|
if length(varargin) == 2 && isa(varargin{1},'char') && isa(varargin{2},'gtsam.KeyFormatter')
|
||||||
class_wrapper(59, this, varargin{:});
|
class_wrapper(65, this, varargin{:});
|
||||||
return
|
return
|
||||||
end
|
end
|
||||||
error('Arguments do not match any overload of function MyFactorPosePoint2.print');
|
error('Arguments do not match any overload of function MyFactorPosePoint2.print');
|
||||||
|
|
|
@ -33,6 +33,8 @@ typedef std::set<boost::shared_ptr<MultipleTemplatesIntFloat>*> Collector_Multip
|
||||||
static Collector_MultipleTemplatesIntFloat collector_MultipleTemplatesIntFloat;
|
static Collector_MultipleTemplatesIntFloat collector_MultipleTemplatesIntFloat;
|
||||||
typedef std::set<boost::shared_ptr<ForwardKinematics>*> Collector_ForwardKinematics;
|
typedef std::set<boost::shared_ptr<ForwardKinematics>*> Collector_ForwardKinematics;
|
||||||
static Collector_ForwardKinematics collector_ForwardKinematics;
|
static Collector_ForwardKinematics collector_ForwardKinematics;
|
||||||
|
typedef std::set<boost::shared_ptr<TemplatedConstructor>*> Collector_TemplatedConstructor;
|
||||||
|
static Collector_TemplatedConstructor collector_TemplatedConstructor;
|
||||||
typedef std::set<boost::shared_ptr<MyFactorPosePoint2>*> Collector_MyFactorPosePoint2;
|
typedef std::set<boost::shared_ptr<MyFactorPosePoint2>*> Collector_MyFactorPosePoint2;
|
||||||
static Collector_MyFactorPosePoint2 collector_MyFactorPosePoint2;
|
static Collector_MyFactorPosePoint2 collector_MyFactorPosePoint2;
|
||||||
|
|
||||||
|
@ -97,6 +99,12 @@ void _deleteAllObjects()
|
||||||
collector_ForwardKinematics.erase(iter++);
|
collector_ForwardKinematics.erase(iter++);
|
||||||
anyDeleted = true;
|
anyDeleted = true;
|
||||||
} }
|
} }
|
||||||
|
{ for(Collector_TemplatedConstructor::iterator iter = collector_TemplatedConstructor.begin();
|
||||||
|
iter != collector_TemplatedConstructor.end(); ) {
|
||||||
|
delete *iter;
|
||||||
|
collector_TemplatedConstructor.erase(iter++);
|
||||||
|
anyDeleted = true;
|
||||||
|
} }
|
||||||
{ for(Collector_MyFactorPosePoint2::iterator iter = collector_MyFactorPosePoint2.begin();
|
{ for(Collector_MyFactorPosePoint2::iterator iter = collector_MyFactorPosePoint2.begin();
|
||||||
iter != collector_MyFactorPosePoint2.end(); ) {
|
iter != collector_MyFactorPosePoint2.end(); ) {
|
||||||
delete *iter;
|
delete *iter;
|
||||||
|
@ -682,7 +690,76 @@ void ForwardKinematics_deconstructor_55(int nargout, mxArray *out[], int nargin,
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void MyFactorPosePoint2_collectorInsertAndMakeBase_56(int nargout, mxArray *out[], int nargin, const mxArray *in[])
|
void TemplatedConstructor_collectorInsertAndMakeBase_56(int nargout, mxArray *out[], int nargin, const mxArray *in[])
|
||||||
|
{
|
||||||
|
mexAtExit(&_deleteAllObjects);
|
||||||
|
typedef boost::shared_ptr<TemplatedConstructor> Shared;
|
||||||
|
|
||||||
|
Shared *self = *reinterpret_cast<Shared**> (mxGetData(in[0]));
|
||||||
|
collector_TemplatedConstructor.insert(self);
|
||||||
|
}
|
||||||
|
|
||||||
|
void TemplatedConstructor_constructor_57(int nargout, mxArray *out[], int nargin, const mxArray *in[])
|
||||||
|
{
|
||||||
|
mexAtExit(&_deleteAllObjects);
|
||||||
|
typedef boost::shared_ptr<TemplatedConstructor> Shared;
|
||||||
|
|
||||||
|
Shared *self = new Shared(new TemplatedConstructor());
|
||||||
|
collector_TemplatedConstructor.insert(self);
|
||||||
|
out[0] = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL);
|
||||||
|
*reinterpret_cast<Shared**> (mxGetData(out[0])) = self;
|
||||||
|
}
|
||||||
|
|
||||||
|
void TemplatedConstructor_constructor_58(int nargout, mxArray *out[], int nargin, const mxArray *in[])
|
||||||
|
{
|
||||||
|
mexAtExit(&_deleteAllObjects);
|
||||||
|
typedef boost::shared_ptr<TemplatedConstructor> Shared;
|
||||||
|
|
||||||
|
string& arg = *unwrap_shared_ptr< string >(in[0], "ptr_string");
|
||||||
|
Shared *self = new Shared(new TemplatedConstructor(arg));
|
||||||
|
collector_TemplatedConstructor.insert(self);
|
||||||
|
out[0] = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL);
|
||||||
|
*reinterpret_cast<Shared**> (mxGetData(out[0])) = self;
|
||||||
|
}
|
||||||
|
|
||||||
|
void TemplatedConstructor_constructor_59(int nargout, mxArray *out[], int nargin, const mxArray *in[])
|
||||||
|
{
|
||||||
|
mexAtExit(&_deleteAllObjects);
|
||||||
|
typedef boost::shared_ptr<TemplatedConstructor> Shared;
|
||||||
|
|
||||||
|
int arg = unwrap< int >(in[0]);
|
||||||
|
Shared *self = new Shared(new TemplatedConstructor(arg));
|
||||||
|
collector_TemplatedConstructor.insert(self);
|
||||||
|
out[0] = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL);
|
||||||
|
*reinterpret_cast<Shared**> (mxGetData(out[0])) = self;
|
||||||
|
}
|
||||||
|
|
||||||
|
void TemplatedConstructor_constructor_60(int nargout, mxArray *out[], int nargin, const mxArray *in[])
|
||||||
|
{
|
||||||
|
mexAtExit(&_deleteAllObjects);
|
||||||
|
typedef boost::shared_ptr<TemplatedConstructor> Shared;
|
||||||
|
|
||||||
|
double arg = unwrap< double >(in[0]);
|
||||||
|
Shared *self = new Shared(new TemplatedConstructor(arg));
|
||||||
|
collector_TemplatedConstructor.insert(self);
|
||||||
|
out[0] = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL);
|
||||||
|
*reinterpret_cast<Shared**> (mxGetData(out[0])) = self;
|
||||||
|
}
|
||||||
|
|
||||||
|
void TemplatedConstructor_deconstructor_61(int nargout, mxArray *out[], int nargin, const mxArray *in[])
|
||||||
|
{
|
||||||
|
typedef boost::shared_ptr<TemplatedConstructor> Shared;
|
||||||
|
checkArguments("delete_TemplatedConstructor",nargout,nargin,1);
|
||||||
|
Shared *self = *reinterpret_cast<Shared**>(mxGetData(in[0]));
|
||||||
|
Collector_TemplatedConstructor::iterator item;
|
||||||
|
item = collector_TemplatedConstructor.find(self);
|
||||||
|
if(item != collector_TemplatedConstructor.end()) {
|
||||||
|
delete self;
|
||||||
|
collector_TemplatedConstructor.erase(item);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void MyFactorPosePoint2_collectorInsertAndMakeBase_62(int nargout, mxArray *out[], int nargin, const mxArray *in[])
|
||||||
{
|
{
|
||||||
mexAtExit(&_deleteAllObjects);
|
mexAtExit(&_deleteAllObjects);
|
||||||
typedef boost::shared_ptr<MyFactor<gtsam::Pose2, gtsam::Matrix>> Shared;
|
typedef boost::shared_ptr<MyFactor<gtsam::Pose2, gtsam::Matrix>> Shared;
|
||||||
|
@ -691,7 +768,7 @@ void MyFactorPosePoint2_collectorInsertAndMakeBase_56(int nargout, mxArray *out[
|
||||||
collector_MyFactorPosePoint2.insert(self);
|
collector_MyFactorPosePoint2.insert(self);
|
||||||
}
|
}
|
||||||
|
|
||||||
void MyFactorPosePoint2_constructor_57(int nargout, mxArray *out[], int nargin, const mxArray *in[])
|
void MyFactorPosePoint2_constructor_63(int nargout, mxArray *out[], int nargin, const mxArray *in[])
|
||||||
{
|
{
|
||||||
mexAtExit(&_deleteAllObjects);
|
mexAtExit(&_deleteAllObjects);
|
||||||
typedef boost::shared_ptr<MyFactor<gtsam::Pose2, gtsam::Matrix>> Shared;
|
typedef boost::shared_ptr<MyFactor<gtsam::Pose2, gtsam::Matrix>> Shared;
|
||||||
|
@ -706,7 +783,7 @@ void MyFactorPosePoint2_constructor_57(int nargout, mxArray *out[], int nargin,
|
||||||
*reinterpret_cast<Shared**> (mxGetData(out[0])) = self;
|
*reinterpret_cast<Shared**> (mxGetData(out[0])) = self;
|
||||||
}
|
}
|
||||||
|
|
||||||
void MyFactorPosePoint2_deconstructor_58(int nargout, mxArray *out[], int nargin, const mxArray *in[])
|
void MyFactorPosePoint2_deconstructor_64(int nargout, mxArray *out[], int nargin, const mxArray *in[])
|
||||||
{
|
{
|
||||||
typedef boost::shared_ptr<MyFactor<gtsam::Pose2, gtsam::Matrix>> Shared;
|
typedef boost::shared_ptr<MyFactor<gtsam::Pose2, gtsam::Matrix>> Shared;
|
||||||
checkArguments("delete_MyFactorPosePoint2",nargout,nargin,1);
|
checkArguments("delete_MyFactorPosePoint2",nargout,nargin,1);
|
||||||
|
@ -719,7 +796,7 @@ void MyFactorPosePoint2_deconstructor_58(int nargout, mxArray *out[], int nargin
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void MyFactorPosePoint2_print_59(int nargout, mxArray *out[], int nargin, const mxArray *in[])
|
void MyFactorPosePoint2_print_65(int nargout, mxArray *out[], int nargin, const mxArray *in[])
|
||||||
{
|
{
|
||||||
checkArguments("print",nargout,nargin-1,2);
|
checkArguments("print",nargout,nargin-1,2);
|
||||||
auto obj = unwrap_shared_ptr<MyFactor<gtsam::Pose2, gtsam::Matrix>>(in[0], "ptr_MyFactorPosePoint2");
|
auto obj = unwrap_shared_ptr<MyFactor<gtsam::Pose2, gtsam::Matrix>>(in[0], "ptr_MyFactorPosePoint2");
|
||||||
|
@ -909,16 +986,34 @@ void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[])
|
||||||
ForwardKinematics_deconstructor_55(nargout, out, nargin-1, in+1);
|
ForwardKinematics_deconstructor_55(nargout, out, nargin-1, in+1);
|
||||||
break;
|
break;
|
||||||
case 56:
|
case 56:
|
||||||
MyFactorPosePoint2_collectorInsertAndMakeBase_56(nargout, out, nargin-1, in+1);
|
TemplatedConstructor_collectorInsertAndMakeBase_56(nargout, out, nargin-1, in+1);
|
||||||
break;
|
break;
|
||||||
case 57:
|
case 57:
|
||||||
MyFactorPosePoint2_constructor_57(nargout, out, nargin-1, in+1);
|
TemplatedConstructor_constructor_57(nargout, out, nargin-1, in+1);
|
||||||
break;
|
break;
|
||||||
case 58:
|
case 58:
|
||||||
MyFactorPosePoint2_deconstructor_58(nargout, out, nargin-1, in+1);
|
TemplatedConstructor_constructor_58(nargout, out, nargin-1, in+1);
|
||||||
break;
|
break;
|
||||||
case 59:
|
case 59:
|
||||||
MyFactorPosePoint2_print_59(nargout, out, nargin-1, in+1);
|
TemplatedConstructor_constructor_59(nargout, out, nargin-1, in+1);
|
||||||
|
break;
|
||||||
|
case 60:
|
||||||
|
TemplatedConstructor_constructor_60(nargout, out, nargin-1, in+1);
|
||||||
|
break;
|
||||||
|
case 61:
|
||||||
|
TemplatedConstructor_deconstructor_61(nargout, out, nargin-1, in+1);
|
||||||
|
break;
|
||||||
|
case 62:
|
||||||
|
MyFactorPosePoint2_collectorInsertAndMakeBase_62(nargout, out, nargin-1, in+1);
|
||||||
|
break;
|
||||||
|
case 63:
|
||||||
|
MyFactorPosePoint2_constructor_63(nargout, out, nargin-1, in+1);
|
||||||
|
break;
|
||||||
|
case 64:
|
||||||
|
MyFactorPosePoint2_deconstructor_64(nargout, out, nargin-1, in+1);
|
||||||
|
break;
|
||||||
|
case 65:
|
||||||
|
MyFactorPosePoint2_print_65(nargout, out, nargin-1, in+1);
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
} catch(const std::exception& e) {
|
} catch(const std::exception& e) {
|
||||||
|
|
|
@ -86,6 +86,12 @@ PYBIND11_MODULE(class_py, m_) {
|
||||||
py::class_<ForwardKinematics, std::shared_ptr<ForwardKinematics>>(m_, "ForwardKinematics")
|
py::class_<ForwardKinematics, std::shared_ptr<ForwardKinematics>>(m_, "ForwardKinematics")
|
||||||
.def(py::init<const gtdynamics::Robot&, const string&, const string&, const gtsam::Values&, const gtsam::Pose3&>(), py::arg("robot"), py::arg("start_link_name"), py::arg("end_link_name"), py::arg("joint_angles"), py::arg("l2Tp") = gtsam::Pose3());
|
.def(py::init<const gtdynamics::Robot&, const string&, const string&, const gtsam::Values&, const gtsam::Pose3&>(), py::arg("robot"), py::arg("start_link_name"), py::arg("end_link_name"), py::arg("joint_angles"), py::arg("l2Tp") = gtsam::Pose3());
|
||||||
|
|
||||||
|
py::class_<TemplatedConstructor, std::shared_ptr<TemplatedConstructor>>(m_, "TemplatedConstructor")
|
||||||
|
.def(py::init<>())
|
||||||
|
.def(py::init<const string&>(), py::arg("arg"))
|
||||||
|
.def(py::init<const int&>(), py::arg("arg"))
|
||||||
|
.def(py::init<const double&>(), py::arg("arg"));
|
||||||
|
|
||||||
py::class_<MyFactor<gtsam::Pose2, gtsam::Matrix>, std::shared_ptr<MyFactor<gtsam::Pose2, gtsam::Matrix>>>(m_, "MyFactorPosePoint2")
|
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(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)
|
.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)
|
||||||
|
|
|
@ -69,6 +69,16 @@ PYBIND11_MODULE(enum_py, m_) {
|
||||||
.value("Groot", gtsam::MCU::GotG::Groot);
|
.value("Groot", gtsam::MCU::GotG::Groot);
|
||||||
|
|
||||||
|
|
||||||
|
py::class_<gtsam::Optimizer<gtsam::GaussNewtonParams>, std::shared_ptr<gtsam::Optimizer<gtsam::GaussNewtonParams>>> optimizergaussnewtonparams(m_gtsam, "OptimizerGaussNewtonParams");
|
||||||
|
optimizergaussnewtonparams
|
||||||
|
.def("setVerbosity",[](gtsam::Optimizer<gtsam::GaussNewtonParams>* self, const Optimizer<gtsam::GaussNewtonParams>::Verbosity value){ self->setVerbosity(value);}, py::arg("value"));
|
||||||
|
|
||||||
|
py::enum_<gtsam::Optimizer<gtsam::GaussNewtonParams>::Verbosity>(optimizergaussnewtonparams, "Verbosity", py::arithmetic())
|
||||||
|
.value("SILENT", gtsam::Optimizer<gtsam::GaussNewtonParams>::Verbosity::SILENT)
|
||||||
|
.value("SUMMARY", gtsam::Optimizer<gtsam::GaussNewtonParams>::Verbosity::SUMMARY)
|
||||||
|
.value("VERBOSE", gtsam::Optimizer<gtsam::GaussNewtonParams>::Verbosity::VERBOSE);
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
#include "python/specializations.h"
|
#include "python/specializations.h"
|
||||||
|
|
||||||
|
|
|
@ -7,6 +7,7 @@ class FunRange {
|
||||||
|
|
||||||
template<M={double}>
|
template<M={double}>
|
||||||
class Fun {
|
class Fun {
|
||||||
|
|
||||||
static This staticMethodWithThis();
|
static This staticMethodWithThis();
|
||||||
|
|
||||||
template<T={string}>
|
template<T={string}>
|
||||||
|
@ -118,5 +119,14 @@ class ForwardKinematics {
|
||||||
const gtsam::Pose3& l2Tp = gtsam::Pose3());
|
const gtsam::Pose3& l2Tp = gtsam::Pose3());
|
||||||
};
|
};
|
||||||
|
|
||||||
|
// Test for templated constructor
|
||||||
|
class TemplatedConstructor {
|
||||||
|
TemplatedConstructor();
|
||||||
|
|
||||||
|
template<T={string, int, double}>
|
||||||
|
TemplatedConstructor(const T& arg);
|
||||||
|
};
|
||||||
|
|
||||||
|
|
||||||
class SuperCoolFactor;
|
class SuperCoolFactor;
|
||||||
typedef SuperCoolFactor<gtsam::Pose3> SuperCoolFactorPose3;
|
typedef SuperCoolFactor<gtsam::Pose3> SuperCoolFactorPose3;
|
||||||
|
|
|
@ -42,4 +42,17 @@ class MCU {
|
||||||
|
|
||||||
};
|
};
|
||||||
|
|
||||||
|
template<PARAMS>
|
||||||
|
class Optimizer {
|
||||||
|
enum Verbosity {
|
||||||
|
SILENT,
|
||||||
|
SUMMARY,
|
||||||
|
VERBOSE
|
||||||
|
};
|
||||||
|
|
||||||
|
void setVerbosity(const This::Verbosity value);
|
||||||
|
};
|
||||||
|
|
||||||
|
typedef gtsam::Optimizer<gtsam::GaussNewtonParams> OptimizerGaussNewtonParams;
|
||||||
|
|
||||||
} // namespace gtsam
|
} // namespace gtsam
|
||||||
|
|
|
@ -314,6 +314,25 @@ class TestInterfaceParser(unittest.TestCase):
|
||||||
self.assertEqual(5, len(ret.args))
|
self.assertEqual(5, len(ret.args))
|
||||||
self.assertEqual("gtsam::Pose3()", ret.args.list()[4].default)
|
self.assertEqual("gtsam::Pose3()", ret.args.list()[4].default)
|
||||||
|
|
||||||
|
def test_constructor_templated(self):
|
||||||
|
"""Test for templated class constructor."""
|
||||||
|
f = """
|
||||||
|
template<T = {double, int}>
|
||||||
|
Class();
|
||||||
|
"""
|
||||||
|
ret = Constructor.rule.parseString(f)[0]
|
||||||
|
self.assertEqual("Class", ret.name)
|
||||||
|
self.assertEqual(0, len(ret.args))
|
||||||
|
|
||||||
|
f = """
|
||||||
|
template<T = {double, int}>
|
||||||
|
Class(const T& name);
|
||||||
|
"""
|
||||||
|
ret = Constructor.rule.parseString(f)[0]
|
||||||
|
self.assertEqual("Class", ret.name)
|
||||||
|
self.assertEqual(1, len(ret.args))
|
||||||
|
self.assertEqual("const T & name", ret.args.args_list[0].to_cpp())
|
||||||
|
|
||||||
def test_operator_overload(self):
|
def test_operator_overload(self):
|
||||||
"""Test for operator overloading."""
|
"""Test for operator overloading."""
|
||||||
# Unary operator
|
# Unary operator
|
||||||
|
|
Loading…
Reference in New Issue