Merge branch 'develop' into feature/update_print_wrap

release/4.3a0
Varun Agrawal 2021-04-20 17:32:55 -04:00
commit 323a15d56c
43 changed files with 438 additions and 121 deletions

View File

@ -8,7 +8,10 @@ public:
Vector evaluateError(const Pose2& q, Vector evaluateError(const Pose2& q,
boost::optional<Matrix&> H = boost::none) const boost::optional<Matrix&> H = boost::none) const
{ {
if (H) (*H) = (Matrix(2,3)<< 1.0,0.0,0.0, 0.0,1.0,0.0).finished(); const Rot2& R = q.rotation();
if (H) (*H) = (gtsam::Matrix(2, 3) <<
R.c(), -R.s(), 0.0,
R.s(), R.c(), 0.0).finished();
return (Vector(2) << q.x() - mx_, q.y() - my_).finished(); return (Vector(2) << q.x() - mx_, q.y() - my_).finished();
} }
}; };

View File

@ -1,7 +1,9 @@
#LyX 2.1 created this file. For more info see http://www.lyx.org/ #LyX 2.2 created this file. For more info see http://www.lyx.org/
\lyxformat 474 \lyxformat 508
\begin_document \begin_document
\begin_header \begin_header
\save_transient_properties true
\origin unavailable
\textclass article \textclass article
\begin_preamble \begin_preamble
\usepackage{times} \usepackage{times}
@ -50,16 +52,16 @@
\language_package default \language_package default
\inputencoding auto \inputencoding auto
\fontencoding T1 \fontencoding T1
\font_roman ae \font_roman "ae" "default"
\font_sans default \font_sans "default" "default"
\font_typewriter default \font_typewriter "default" "default"
\font_math auto \font_math "auto" "auto"
\font_default_family rmdefault \font_default_family rmdefault
\use_non_tex_fonts false \use_non_tex_fonts false
\font_sc false \font_sc false
\font_osf false \font_osf false
\font_sf_scale 100 \font_sf_scale 100 100
\font_tt_scale 100 \font_tt_scale 100 100
\graphics default \graphics default
\default_output_format default \default_output_format default
\output_sync 0 \output_sync 0
@ -1061,7 +1063,7 @@ noindent
\begin_layout Subsection \begin_layout Subsection
\begin_inset CommandInset label \begin_inset CommandInset label
LatexCommand label LatexCommand label
name "sub:Full-Posterior-Inference" name "subsec:Full-Posterior-Inference"
\end_inset \end_inset
@ -1272,7 +1274,7 @@ ing to odometry measurements.
(see Section (see Section
\begin_inset CommandInset ref \begin_inset CommandInset ref
LatexCommand ref LatexCommand ref
reference "sub:Full-Posterior-Inference" reference "subsec:Full-Posterior-Inference"
\end_inset \end_inset
@ -1469,7 +1471,7 @@ GPS-like
\begin_inset CommandInset include \begin_inset CommandInset include
LatexCommand lstinputlisting LatexCommand lstinputlisting
filename "Code/LocalizationFactor.cpp" filename "Code/LocalizationFactor.cpp"
lstparams "aboveskip=10pt,basicstyle={\\ttfamily\\small},caption={Excerpt from examples/LocalizationExample.cpp},captionpos=b,frame=single,identifierstyle={\\bfseries},label={listing:LocalizationFactor},language={C++},numbers=left" lstparams "aboveskip=10pt,basicstyle={\\ttfamily\\small},captionpos=b,frame=single,identifierstyle={\\bfseries},language={C++},numbers=left,caption={Excerpt from examples/LocalizationExample.cpp},label={listing:LocalizationFactor}"
\end_inset \end_inset
@ -1590,15 +1592,15 @@ q_{y}
\begin_inset Formula $2\times3$ \begin_inset Formula $2\times3$
\end_inset \end_inset
matrix: matrix in tangent space which is the same the as the rotation matrix:
\end_layout \end_layout
\begin_layout Standard \begin_layout Standard
\begin_inset Formula \begin_inset Formula
\[ \[
H=\left[\begin{array}{ccc} H=\left[\begin{array}{ccc}
1 & 0 & 0\\ \cos(q_{\theta}) & -\sin(q_{\theta}) & 0\\
0 & 1 & 0 \sin(q_{\theta}) & \cos(q_{\theta}) & 0
\end{array}\right] \end{array}\right]
\] \]
@ -1750,7 +1752,7 @@ global
The marginals can be recovered exactly as in Section The marginals can be recovered exactly as in Section
\begin_inset CommandInset ref \begin_inset CommandInset ref
LatexCommand ref LatexCommand ref
reference "sub:Full-Posterior-Inference" reference "subsec:Full-Posterior-Inference"
\end_inset \end_inset
@ -1770,7 +1772,7 @@ filename "Code/LocalizationOutput5.txt"
Comparing this with the covariance matrices in Section Comparing this with the covariance matrices in Section
\begin_inset CommandInset ref \begin_inset CommandInset ref
LatexCommand ref LatexCommand ref
reference "sub:Full-Posterior-Inference" reference "subsec:Full-Posterior-Inference"
\end_inset \end_inset

Binary file not shown.

View File

@ -84,15 +84,16 @@ class UnaryFactor: public NoiseModelFactor1<Pose2> {
// The first is the 'evaluateError' function. This function implements the desired measurement // The first is the 'evaluateError' function. This function implements the desired measurement
// function, returning a vector of errors when evaluated at the provided variable value. It // function, returning a vector of errors when evaluated at the provided variable value. It
// must also calculate the Jacobians for this measurement function, if requested. // must also calculate the Jacobians for this measurement function, if requested.
Vector evaluateError(const Pose2& q, Vector evaluateError(const Pose2& q, boost::optional<Matrix&> H = boost::none) const override {
boost::optional<Matrix&> H = boost::none) const override { // The measurement function for a GPS-like measurement h(q) which predicts the measurement (m) is h(q) = q, q = [qx qy qtheta]
// The measurement function for a GPS-like measurement is simple: // The error is then simply calculated as E(q) = h(q) - m:
// error_x = pose.x - measurement.x // error_x = q.x - mx
// error_y = pose.y - measurement.y // error_y = q.y - my
// Consequently, the Jacobians are: // Node's orientation reflects in the Jacobian, in tangent space this is equal to the right-hand rule rotation matrix
// [ derror_x/dx derror_x/dy derror_x/dtheta ] = [1 0 0] // H = [ cos(q.theta) -sin(q.theta) 0 ]
// [ derror_y/dx derror_y/dy derror_y/dtheta ] = [0 1 0] // [ sin(q.theta) cos(q.theta) 0 ]
if (H) (*H) = (Matrix(2, 3) << 1.0, 0.0, 0.0, 0.0, 1.0, 0.0).finished(); const Rot2& R = q.rotation();
if (H) (*H) = (gtsam::Matrix(2, 3) << R.c(), -R.s(), 0.0, R.s(), R.c(), 0.0).finished();
return (Vector(2) << q.x() - mx_, q.y() - my_).finished(); return (Vector(2) << q.x() - mx_, q.y() - my_).finished();
} }

View File

@ -22,6 +22,8 @@
#include <list> #include <list>
#include <boost/utility/enable_if.hpp> #include <boost/utility/enable_if.hpp>
#include <boost/serialization/nvp.hpp> #include <boost/serialization/nvp.hpp>
#include <boost/serialization/version.hpp>
#include <boost/serialization/optional.hpp>
#include <boost/serialization/list.hpp> #include <boost/serialization/list.hpp>
namespace gtsam { namespace gtsam {

View File

@ -825,7 +825,7 @@ TEST(Rot3, RQ_derivative) {
const auto R = Rot3::RzRyRx(xyz).matrix(); const auto R = Rot3::RzRyRx(xyz).matrix();
const auto num = numericalDerivative11(RQ_proxy, R); const auto num = numericalDerivative11(RQ_proxy, R);
Matrix39 calc; Matrix39 calc;
auto dummy = RQ(R, calc).second; RQ(R, calc).second;
const auto err = vec_err.second; const auto err = vec_err.second;
CHECK(assert_equal(num, calc, err)); CHECK(assert_equal(num, calc, err));

View File

@ -2583,9 +2583,6 @@ class NonlinearISAM {
//************************************************************************* //*************************************************************************
// Nonlinear factor types // Nonlinear factor types
//************************************************************************* //*************************************************************************
#include <gtsam/geometry/CalibratedCamera.h>
#include <gtsam/geometry/StereoPoint2.h>
#include <gtsam/nonlinear/PriorFactor.h> #include <gtsam/nonlinear/PriorFactor.h>
template <T = {double, template <T = {double,
Vector, Vector,

View File

@ -25,10 +25,10 @@
#include <boost/serialization/extended_type_info.hpp> #include <boost/serialization/extended_type_info.hpp>
#include <boost/serialization/nvp.hpp> #include <boost/serialization/nvp.hpp>
#include <boost/serialization/version.hpp>
#include <boost/serialization/optional.hpp> #include <boost/serialization/optional.hpp>
#include <boost/serialization/shared_ptr.hpp> #include <boost/serialization/shared_ptr.hpp>
#include <boost/serialization/singleton.hpp> #include <boost/serialization/singleton.hpp>
#include <boost/serialization/version.hpp>
namespace gtsam { namespace gtsam {
namespace noiseModel { namespace noiseModel {

View File

@ -21,9 +21,9 @@
#include <gtsam/base/types.h> #include <gtsam/base/types.h>
#include <gtsam/dllexport.h> #include <gtsam/dllexport.h>
#include <boost/serialization/version.hpp>
#include <boost/serialization/nvp.hpp> #include <boost/serialization/nvp.hpp>
#include <boost/shared_ptr.hpp> #include <boost/shared_ptr.hpp>
#include <boost/serialization/version.hpp>
#include <vector> #include <vector>

View File

@ -211,9 +211,7 @@ public:
* @param measuredAcc Measured acceleration (in body frame, as given by the * @param measuredAcc Measured acceleration (in body frame, as given by the
* sensor) * sensor)
* @param measuredOmega Measured angular velocity (as given by the sensor) * @param measuredOmega Measured angular velocity (as given by the sensor)
* @param deltaT Time interval between two consecutive IMU measurements * @param dt Time interval between two consecutive IMU measurements
* @param body_P_sensor Optional sensor frame (pose of the IMU in the body
* frame)
*/ */
void integrateMeasurement(const Vector3& measuredAcc, void integrateMeasurement(const Vector3& measuredAcc,
const Vector3& measuredOmega, const double dt) override; const Vector3& measuredOmega, const double dt) override;

View File

@ -106,6 +106,7 @@ void PreintegratedImuMeasurements::mergeWith(const PreintegratedImuMeasurements&
preintMeasCov_ = P + *H2 * pim12.preintMeasCov_ * H2->transpose(); preintMeasCov_ = P + *H2 * pim12.preintMeasCov_ * H2->transpose();
} }
#endif #endif
//------------------------------------------------------------------------------ //------------------------------------------------------------------------------
// ImuFactor methods // ImuFactor methods
//------------------------------------------------------------------------------ //------------------------------------------------------------------------------

View File

@ -192,6 +192,8 @@ public:
* @param pose_j Current pose key * @param pose_j Current pose key
* @param vel_j Current velocity key * @param vel_j Current velocity key
* @param bias Previous bias key * @param bias Previous bias key
* @param preintegratedMeasurements The preintegreated measurements since the
* last pose.
*/ */
ImuFactor(Key pose_i, Key vel_i, Key pose_j, Key vel_j, Key bias, ImuFactor(Key pose_i, Key vel_i, Key pose_j, Key vel_j, Key bias,
const PreintegratedImuMeasurements& preintegratedMeasurements); const PreintegratedImuMeasurements& preintegratedMeasurements);

View File

@ -298,7 +298,7 @@ class GncOptimizer {
break; break;
case GncLossType::TLS: case GncLossType::TLS:
weightsConverged = true; weightsConverged = true;
for (size_t i = 0; i < weights.size(); i++) { for (int i = 0; i < weights.size(); i++) {
if (std::fabs(weights[i] - std::round(weights[i])) if (std::fabs(weights[i] - std::round(weights[i]))
> params_.weightsTol) { > params_.weightsTol) {
weightsConverged = false; weightsConverged = false;

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 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. 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 ## 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: 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. 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 ## Requirements
- If you want to build the GTSAM python library for a specific python version (eg 3.6), - If you want to build the GTSAM python library for a specific python version (eg 3.6),

View File

@ -91,6 +91,13 @@ The python wrapper supports keyword arguments for functions/methods. Hence, the
```cpp ```cpp
template<T, R, S> template<T, R, S>
``` ```
- Global variables
- Similar to global functions, the wrapper supports global variables as well.
- Currently we only support primitive types, such as `double`, `int`, `string`, etc.
- E.g.
```cpp
const double kGravity = -9.81;
```
- Using classes defined in other modules - Using classes defined in other modules
- If you are using a class `OtherClass` not wrapped in an interface file, add `class OtherClass;` as a forward declaration to avoid a dependency error. `OtherClass` should be in the same project. - If you are using a class `OtherClass` not wrapped in an interface file, add `class OtherClass;` as a forward declaration to avoid a dependency error. `OtherClass` should be in the same project.
@ -98,6 +105,7 @@ The python wrapper supports keyword arguments for functions/methods. Hence, the
- Virtual inheritance - Virtual inheritance
- Specify fully-qualified base classes, i.e. `virtual class Derived : ns::Base {` where `ns` is the namespace. - 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 {`. - 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 - Forward declarations must also be marked virtual, e.g. `virtual class ns::Base;` and
also `virtual class ns::Derived;`. also `virtual class ns::Derived;`.
- Pure virtual (abstract) classes should list no constructors in the interface file. - Pure virtual (abstract) classes should list no constructors in the interface file.

View File

@ -72,6 +72,7 @@ function(pybind_wrap
--template --template
${module_template} ${module_template}
${_WRAP_BOOST_ARG} ${_WRAP_BOOST_ARG}
DEPENDS ${interface_header} ${module_template}
VERBATIM) VERBATIM)
add_custom_target(pybind_wrap_${module_name} ALL DEPENDS ${generated_cpp}) add_custom_target(pybind_wrap_${module_name} ALL DEPENDS ${generated_cpp})

View File

@ -19,6 +19,7 @@ from .template import Template
from .tokens import (CLASS, COLON, CONST, IDENT, LBRACE, LPAREN, RBRACE, from .tokens import (CLASS, COLON, CONST, IDENT, LBRACE, LPAREN, RBRACE,
RPAREN, SEMI_COLON, STATIC, VIRTUAL, OPERATOR) RPAREN, SEMI_COLON, STATIC, VIRTUAL, OPERATOR)
from .type import TemplatedType, Type, Typename from .type import TemplatedType, Type, Typename
from .variable import Variable
class Method: class Method:
@ -136,32 +137,6 @@ class Constructor:
return "Constructor: {}".format(self.name) return "Constructor: {}".format(self.name)
class Property:
"""
Rule to parse the variable members of a class.
E.g.
```
class Hello {
string name; // This is a property.
};
````
"""
rule = (
(Type.rule ^ TemplatedType.rule)("ctype") #
+ IDENT("name") #
+ SEMI_COLON #
).setParseAction(lambda t: Property(t.ctype, t.name))
def __init__(self, ctype: Type, name: str, parent=''):
self.ctype = ctype[0] # ParseResult is a list
self.name = name
self.parent = parent
def __repr__(self) -> str:
return '{} {}'.format(self.ctype.__repr__(), self.name)
class Operator: class Operator:
""" """
Rule for parsing operator overloads. Rule for parsing operator overloads.
@ -256,12 +231,12 @@ class Class:
Rule for all the members within a class. Rule for all the members within a class.
""" """
rule = ZeroOrMore(Constructor.rule ^ StaticMethod.rule ^ Method.rule rule = ZeroOrMore(Constructor.rule ^ StaticMethod.rule ^ Method.rule
^ Property.rule ^ Operator.rule).setParseAction( ^ Variable.rule ^ Operator.rule).setParseAction(
lambda t: Class.Members(t.asList())) lambda t: Class.Members(t.asList()))
def __init__(self, def __init__(self,
members: List[Union[Constructor, Method, StaticMethod, members: List[Union[Constructor, Method, StaticMethod,
Property, Operator]]): Variable, Operator]]):
self.ctors = [] self.ctors = []
self.methods = [] self.methods = []
self.static_methods = [] self.static_methods = []
@ -274,12 +249,12 @@ class Class:
self.methods.append(m) self.methods.append(m)
elif isinstance(m, StaticMethod): elif isinstance(m, StaticMethod):
self.static_methods.append(m) self.static_methods.append(m)
elif isinstance(m, Property): elif isinstance(m, Variable):
self.properties.append(m) self.properties.append(m)
elif isinstance(m, Operator): elif isinstance(m, Operator):
self.operators.append(m) self.operators.append(m)
_parent = COLON + Typename.rule("parent_class") _parent = COLON + (TemplatedType.rule ^ Typename.rule)("parent_class")
rule = ( rule = (
Optional(Template.rule("template")) # Optional(Template.rule("template")) #
+ Optional(VIRTUAL("is_virtual")) # + Optional(VIRTUAL("is_virtual")) #
@ -311,7 +286,7 @@ class Class:
ctors: List[Constructor], ctors: List[Constructor],
methods: List[Method], methods: List[Method],
static_methods: List[StaticMethod], static_methods: List[StaticMethod],
properties: List[Property], properties: List[Variable],
operators: List[Operator], operators: List[Operator],
parent: str = '', parent: str = '',
): ):
@ -319,11 +294,16 @@ class Class:
self.is_virtual = is_virtual self.is_virtual = is_virtual
self.name = name self.name = name
if parent_class: if parent_class:
# If it is in an iterable, extract the parent class.
if isinstance(parent_class, Iterable): if isinstance(parent_class, Iterable):
self.parent_class = parent_class[0] parent_class = parent_class[0]
else:
self.parent_class = parent_class
# 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: else:
self.parent_class = '' self.parent_class = ''

View File

@ -15,8 +15,8 @@ from typing import Iterable, List, Union
from pyparsing import Optional, ParseResults, delimitedList from pyparsing import Optional, ParseResults, delimitedList
from .template import Template from .template import Template
from .tokens import (COMMA, IDENT, LOPBRACK, LPAREN, PAIR, ROPBRACK, RPAREN, from .tokens import (COMMA, DEFAULT_ARG, EQUAL, IDENT, LOPBRACK, LPAREN, PAIR,
SEMI_COLON) ROPBRACK, RPAREN, SEMI_COLON)
from .type import TemplatedType, Type from .type import TemplatedType, Type
@ -29,15 +29,29 @@ class Argument:
void sayHello(/*`s` is the method argument with type `const string&`*/ const string& s); void sayHello(/*`s` is the method argument with type `const string&`*/ const string& s);
``` ```
""" """
rule = ((Type.rule ^ TemplatedType.rule)("ctype") + rule = ((Type.rule ^ TemplatedType.rule)("ctype") + IDENT("name") + \
IDENT("name")).setParseAction(lambda t: Argument(t.ctype, t.name)) Optional(EQUAL + (DEFAULT_ARG ^ Type.rule ^ TemplatedType.rule) + \
Optional(LPAREN + RPAREN) # Needed to parse the parens for default constructors
)("default")
).setParseAction(lambda t: Argument(t.ctype, t.name, t.default))
def __init__(self, ctype: Union[Type, TemplatedType], name: str): def __init__(self,
ctype: Union[Type, TemplatedType],
name: str,
default: ParseResults = None):
if isinstance(ctype, Iterable): if isinstance(ctype, Iterable):
self.ctype = ctype[0] self.ctype = ctype[0]
else: else:
self.ctype = ctype self.ctype = ctype
self.name = name self.name = name
# If the length is 1, it's a regular type,
if len(default) == 1:
default = default[0]
# This means a tuple has been passed so we convert accordingly
elif len(default) > 1:
default = tuple(default.asList())
self.default = default
self.parent: Union[ArgumentList, None] = None self.parent: Union[ArgumentList, None] = None
def __repr__(self) -> str: def __repr__(self) -> str:

View File

@ -23,6 +23,7 @@ from .declaration import ForwardDeclaration, Include
from .function import GlobalFunction from .function import GlobalFunction
from .namespace import Namespace from .namespace import Namespace
from .template import TypedefTemplateInstantiation from .template import TypedefTemplateInstantiation
from .variable import Variable
class Module: class Module:
@ -43,6 +44,7 @@ class Module:
^ Class.rule # ^ Class.rule #
^ TypedefTemplateInstantiation.rule # ^ TypedefTemplateInstantiation.rule #
^ GlobalFunction.rule # ^ GlobalFunction.rule #
^ Variable.rule #
^ Namespace.rule # ^ Namespace.rule #
).setParseAction(lambda t: Namespace('', t.asList())) + ).setParseAction(lambda t: Namespace('', t.asList())) +
stringEnd) stringEnd)

View File

@ -22,6 +22,7 @@ from .function import GlobalFunction
from .template import TypedefTemplateInstantiation from .template import TypedefTemplateInstantiation
from .tokens import IDENT, LBRACE, NAMESPACE, RBRACE from .tokens import IDENT, LBRACE, NAMESPACE, RBRACE
from .type import Typename from .type import Typename
from .variable import Variable
def find_sub_namespace(namespace: "Namespace", def find_sub_namespace(namespace: "Namespace",
@ -67,6 +68,7 @@ class Namespace:
^ Class.rule # ^ Class.rule #
^ TypedefTemplateInstantiation.rule # ^ TypedefTemplateInstantiation.rule #
^ GlobalFunction.rule # ^ GlobalFunction.rule #
^ Variable.rule #
^ rule # ^ rule #
)("content") # BR )("content") # BR
+ RBRACE # + RBRACE #

View File

@ -10,7 +10,9 @@ All the token definitions.
Author: Duy Nguyen Ta, Fan Jiang, Matthew Sklar, Varun Agrawal, and Frank Dellaert Author: Duy Nguyen Ta, Fan Jiang, Matthew Sklar, Varun Agrawal, and Frank Dellaert
""" """
from pyparsing import Keyword, Literal, Suppress, Word, alphanums, alphas, nums, Or from pyparsing import (Keyword, Literal, Or, QuotedString, Suppress, Word,
alphanums, alphas, delimitedList, nums,
pyparsing_common)
# rule for identifiers (e.g. variable names) # rule for identifiers (e.g. variable names)
IDENT = Word(alphas + '_', alphanums + '_') ^ Word(nums) IDENT = Word(alphas + '_', alphanums + '_') ^ Word(nums)
@ -19,6 +21,18 @@ RAW_POINTER, SHARED_POINTER, REF = map(Literal, "@*&")
LPAREN, RPAREN, LBRACE, RBRACE, COLON, SEMI_COLON = map(Suppress, "(){}:;") LPAREN, RPAREN, LBRACE, RBRACE, COLON, SEMI_COLON = map(Suppress, "(){}:;")
LOPBRACK, ROPBRACK, COMMA, EQUAL = map(Suppress, "<>,=") LOPBRACK, ROPBRACK, COMMA, EQUAL = map(Suppress, "<>,=")
# Encapsulating type for numbers, and single and double quoted strings.
# The pyparsing_common utilities ensure correct coversion to the corresponding type.
# E.g. pyparsing_common.number will convert 3.1415 to a float type.
NUMBER_OR_STRING = (pyparsing_common.number ^ QuotedString('"') ^ QuotedString("'"))
# A python tuple, e.g. (1, 9, "random", 3.1415)
TUPLE = (LPAREN + delimitedList(NUMBER_OR_STRING) + RPAREN)
# Default argument passed to functions/methods.
DEFAULT_ARG = (NUMBER_OR_STRING ^ pyparsing_common.identifier ^ TUPLE)
CONST, VIRTUAL, CLASS, STATIC, PAIR, TEMPLATE, TYPEDEF, INCLUDE = map( CONST, VIRTUAL, CLASS, STATIC, PAIR, TEMPLATE, TYPEDEF, INCLUDE = map(
Keyword, Keyword,
[ [

View File

@ -203,9 +203,12 @@ class Type:
raise ValueError("Parse result is not a Type") raise ValueError("Parse result is not a Type")
def __repr__(self) -> str: def __repr__(self) -> str:
return "{self.is_const} {self.typename} " \ is_ptr_or_ref = "{0}{1}{2}".format(self.is_shared_ptr, self.is_ptr,
"{self.is_shared_ptr}{self.is_ptr}{self.is_ref}".format( self.is_ref)
self=self) return "{is_const}{self.typename}{is_ptr_or_ref}".format(
self=self,
is_const="const " if self.is_const else "",
is_ptr_or_ref=" " + is_ptr_or_ref if is_ptr_or_ref else "")
def to_cpp(self, use_boost: bool) -> str: def to_cpp(self, use_boost: bool) -> str:
""" """

View File

@ -0,0 +1,53 @@
"""
GTSAM Copyright 2010-2020, Georgia Tech Research Corporation,
Atlanta, Georgia 30332-0415
All Rights Reserved
See LICENSE for the license information
Parser classes and rules for parsing C++ variables.
Author: Varun Agrawal, Gerry Chen
"""
from pyparsing import Optional, ParseResults
from .tokens import DEFAULT_ARG, EQUAL, IDENT, SEMI_COLON, STATIC
from .type import TemplatedType, Type
class Variable:
"""
Rule to parse variables.
Variables are a combination of Type/TemplatedType and the variable identifier.
E.g.
```
class Hello {
string name; // This is a property variable.
};
Vector3 kGravity; // This is a global variable.
````
"""
rule = ((Type.rule ^ TemplatedType.rule)("ctype") #
+ IDENT("name") #
#TODO(Varun) Add support for non-basic types
+ Optional(EQUAL + (DEFAULT_ARG))("default") #
+ SEMI_COLON #
).setParseAction(lambda t: Variable(t.ctype, t.name, t.default))
def __init__(self,
ctype: Type,
name: str,
default: ParseResults = None,
parent=''):
self.ctype = ctype[0] # ParseResult is a list
self.name = name
if default:
self.default = default[0]
self.parent = parent
def __repr__(self) -> str:
return '{} {}'.format(self.ctype.__repr__(), self.name)

View File

@ -45,7 +45,14 @@ class PybindWrapper:
"""Set the argument names in Pybind11 format.""" """Set the argument names in Pybind11 format."""
names = args_list.args_names() names = args_list.args_names()
if names: if names:
py_args = ['py::arg("{}")'.format(name) for name in names] py_args = []
for arg in args_list.args_list:
if arg.default and isinstance(arg.default, str):
arg.default = "\"{arg.default}\"".format(arg=arg)
argument = 'py::arg("{name}"){default}'.format(
name=arg.name,
default=' = {0}'.format(arg.default) if arg.default else '')
py_args.append(argument)
return ", " + ", ".join(py_args) return ", " + ", ".join(py_args)
else: else:
return '' return ''
@ -124,30 +131,29 @@ class PybindWrapper:
suffix=suffix, suffix=suffix,
)) ))
# Create __repr__ override
# We allow all arguments to .print() and let the compiler handle type mismatches.
if method.name == 'print': if method.name == 'print':
type_list = method.args.to_cpp(self.use_boost) # Redirect stdout - see pybind docs for why this is a good idea:
if len(type_list) > 0 and type_list[0].strip() == 'string': # https://pybind11.readthedocs.io/en/stable/advanced/pycpp/utilities.html#capturing-standard-output-from-ostream
ret += '''{prefix}.def("__repr__", ret = ret.replace('self->print', 'py::scoped_ostream_redirect output; self->print')
[](const {cpp_class} &a) {{
# Make __repr__() call print() internally
ret += '''{prefix}.def("__repr__",
[](const {cpp_class}& self{opt_comma}{args_signature_with_names}){{
gtsam::RedirectCout redirect; gtsam::RedirectCout redirect;
a.print(""); self.{method_name}({method_args});
return redirect.str(); return redirect.str();
}}){suffix}'''.format( }}{py_args_names}){suffix}'''.format(
prefix=prefix, prefix=prefix,
cpp_class=cpp_class, cpp_class=cpp_class,
suffix=suffix, opt_comma=', ' if args_names else '',
) args_signature_with_names=args_signature_with_names,
else: method_name=method.name,
ret += '''{prefix}.def("__repr__", method_args=", ".join(args_names) if args_names else '',
[](const {cpp_class} &a) {{ py_args_names=py_args_names,
gtsam::RedirectCout redirect; suffix=suffix)
a.print();
return redirect.str();
}}){suffix}'''.format(
prefix=prefix,
cpp_class=cpp_class,
suffix=suffix,
)
return ret return ret
def wrap_methods(self, methods, cpp_class, prefix='\n' + ' ' * 8, suffix=''): def wrap_methods(self, methods, cpp_class, prefix='\n' + ' ' * 8, suffix=''):
@ -180,6 +186,16 @@ class PybindWrapper:
return res return res
def wrap_variable(self, module, module_var, variable, prefix='\n' + ' ' * 8):
"""Wrap a variable that's not part of a class (i.e. global)
"""
return '{prefix}{module_var}.attr("{variable_name}") = {module}{variable_name};'.format(
prefix=prefix,
module=module,
module_var=module_var,
variable_name=variable.name
)
def wrap_properties(self, properties, cpp_class, prefix='\n' + ' ' * 8): def wrap_properties(self, properties, cpp_class, prefix='\n' + ' ' * 8):
"""Wrap all the properties in the `cpp_class`.""" """Wrap all the properties in the `cpp_class`."""
res = "" res = ""
@ -335,6 +351,13 @@ class PybindWrapper:
includes += includes_namespace includes += includes_namespace
elif isinstance(element, instantiator.InstantiatedClass): elif isinstance(element, instantiator.InstantiatedClass):
wrapped += self.wrap_instantiated_class(element) wrapped += self.wrap_instantiated_class(element)
elif isinstance(element, parser.Variable):
wrapped += self.wrap_variable(
module=self._add_namespaces('', namespaces),
module_var=module_var,
variable=element,
prefix='\n' + ' ' * 4
)
# Global functions. # Global functions.
all_funcs = [ all_funcs = [

View File

@ -95,8 +95,10 @@ def instantiate_args_list(args_list, template_typenames, instantiations,
for arg in args_list: for arg in args_list:
new_type = instantiate_type(arg.ctype, template_typenames, new_type = instantiate_type(arg.ctype, template_typenames,
instantiations, cpp_typename) instantiations, cpp_typename)
default = [arg.default] if isinstance(arg, parser.Argument) else ''
instantiated_args.append(parser.Argument(name=arg.name, instantiated_args.append(parser.Argument(name=arg.name,
ctype=new_type)) ctype=new_type,
default=default))
return instantiated_args return instantiated_args

View File

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

View File

@ -4,6 +4,9 @@
%-------Constructors------- %-------Constructors-------
%MyFactorPosePoint2(size_t key1, size_t key2, double measured, Base noiseModel) %MyFactorPosePoint2(size_t key1, size_t key2, double measured, Base noiseModel)
% %
%-------Methods-------
%print(string s, KeyFormatter keyFormatter) : returns void
%
classdef MyFactorPosePoint2 < handle classdef MyFactorPosePoint2 < handle
properties properties
ptr_MyFactorPosePoint2 = 0 ptr_MyFactorPosePoint2 = 0
@ -29,6 +32,16 @@ classdef MyFactorPosePoint2 < handle
%DISPLAY Calls print on the object %DISPLAY Calls print on the object
function disp(obj), obj.display; end function disp(obj), obj.display; end
%DISP Calls print on the object %DISP Calls print on the object
function varargout = print(this, varargin)
% 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(55, this, varargin{:});
return
end
error('Arguments do not match any overload of function MyFactorPosePoint2.print');
end
end end
methods(Static = true) methods(Static = true)

View File

@ -1,6 +1,6 @@
function varargout = TemplatedFunctionRot3(varargin) function varargout = TemplatedFunctionRot3(varargin)
if length(varargin) == 1 && isa(varargin{1},'gtsam.Rot3') if length(varargin) == 1 && isa(varargin{1},'gtsam.Rot3')
functions_wrapper(8, varargin{:}); functions_wrapper(11, varargin{:});
else else
error('Arguments do not match any overload of function TemplatedFunctionRot3'); error('Arguments do not match any overload of function TemplatedFunctionRot3');
end end

View File

@ -661,6 +661,15 @@ void MyFactorPosePoint2_deconstructor_54(int nargout, mxArray *out[], int nargin
} }
} }
void MyFactorPosePoint2_print_55(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");
string& s = *unwrap_shared_ptr< string >(in[1], "ptr_string");
gtsam::KeyFormatter& keyFormatter = *unwrap_shared_ptr< gtsam::KeyFormatter >(in[2], "ptr_gtsamKeyFormatter");
obj->print(s,keyFormatter);
}
void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{ {
@ -838,6 +847,9 @@ void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[])
case 54: case 54:
MyFactorPosePoint2_deconstructor_54(nargout, out, nargin-1, in+1); MyFactorPosePoint2_deconstructor_54(nargout, out, nargin-1, in+1);
break; break;
case 55:
MyFactorPosePoint2_print_55(nargout, out, nargin-1, in+1);
break;
} }
} catch(const std::exception& e) { } catch(const std::exception& e) {
mexErrMsgTxt(("Exception from gtsam:\n" + std::string(e.what()) + "\n").c_str()); mexErrMsgTxt(("Exception from gtsam:\n" + std::string(e.what()) + "\n").c_str());

View File

@ -196,7 +196,25 @@ void MultiTemplatedFunctionDoubleSize_tDouble_7(int nargout, mxArray *out[], int
size_t y = unwrap< size_t >(in[1]); size_t y = unwrap< size_t >(in[1]);
out[0] = wrap< double >(MultiTemplatedFunctionDoubleSize_tDouble(x,y)); out[0] = wrap< double >(MultiTemplatedFunctionDoubleSize_tDouble(x,y));
} }
void TemplatedFunctionRot3_8(int nargout, mxArray *out[], int nargin, const mxArray *in[]) void DefaultFuncInt_8(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
checkArguments("DefaultFuncInt",nargout,nargin,1);
int a = unwrap< int >(in[0]);
DefaultFuncInt(a);
}
void DefaultFuncString_9(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
checkArguments("DefaultFuncString",nargout,nargin,1);
string& s = *unwrap_shared_ptr< string >(in[0], "ptr_string");
DefaultFuncString(s);
}
void DefaultFuncObj_10(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
checkArguments("DefaultFuncObj",nargout,nargin,1);
gtsam::KeyFormatter& keyFormatter = *unwrap_shared_ptr< gtsam::KeyFormatter >(in[0], "ptr_gtsamKeyFormatter");
DefaultFuncObj(keyFormatter);
}
void TemplatedFunctionRot3_11(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{ {
checkArguments("TemplatedFunctionRot3",nargout,nargin,1); checkArguments("TemplatedFunctionRot3",nargout,nargin,1);
gtsam::Rot3& t = *unwrap_shared_ptr< gtsam::Rot3 >(in[0], "ptr_gtsamRot3"); gtsam::Rot3& t = *unwrap_shared_ptr< gtsam::Rot3 >(in[0], "ptr_gtsamRot3");
@ -239,7 +257,16 @@ void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[])
MultiTemplatedFunctionDoubleSize_tDouble_7(nargout, out, nargin-1, in+1); MultiTemplatedFunctionDoubleSize_tDouble_7(nargout, out, nargin-1, in+1);
break; break;
case 8: case 8:
TemplatedFunctionRot3_8(nargout, out, nargin-1, in+1); DefaultFuncInt_8(nargout, out, nargin-1, in+1);
break;
case 9:
DefaultFuncString_9(nargout, out, nargin-1, in+1);
break;
case 10:
DefaultFuncObj_10(nargout, out, nargin-1, in+1);
break;
case 11:
TemplatedFunctionRot3_11(nargout, out, nargin-1, in+1);
break; break;
} }
} catch(const std::exception& e) { } catch(const std::exception& e) {

View File

@ -50,6 +50,8 @@ typedef std::set<boost::shared_ptr<MyTemplatePoint2>*> Collector_MyTemplatePoint
static Collector_MyTemplatePoint2 collector_MyTemplatePoint2; static Collector_MyTemplatePoint2 collector_MyTemplatePoint2;
typedef std::set<boost::shared_ptr<MyTemplateMatrix>*> Collector_MyTemplateMatrix; typedef std::set<boost::shared_ptr<MyTemplateMatrix>*> Collector_MyTemplateMatrix;
static Collector_MyTemplateMatrix collector_MyTemplateMatrix; static Collector_MyTemplateMatrix collector_MyTemplateMatrix;
typedef std::set<boost::shared_ptr<ForwardKinematicsFactor>*> Collector_ForwardKinematicsFactor;
static Collector_ForwardKinematicsFactor collector_ForwardKinematicsFactor;
void _deleteAllObjects() void _deleteAllObjects()
{ {
@ -141,6 +143,12 @@ void _deleteAllObjects()
collector_MyTemplateMatrix.erase(iter++); collector_MyTemplateMatrix.erase(iter++);
anyDeleted = true; anyDeleted = true;
} } } }
{ for(Collector_ForwardKinematicsFactor::iterator iter = collector_ForwardKinematicsFactor.begin();
iter != collector_ForwardKinematicsFactor.end(); ) {
delete *iter;
collector_ForwardKinematicsFactor.erase(iter++);
anyDeleted = true;
} }
if(anyDeleted) if(anyDeleted)
cout << cout <<
"WARNING: Wrap modules with variables in the workspace have been reloaded due to\n" "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(MyBase).name(), "MyBase"));
types.insert(std::make_pair(typeid(MyTemplatePoint2).name(), "MyTemplatePoint2")); types.insert(std::make_pair(typeid(MyTemplatePoint2).name(), "MyTemplatePoint2"));
types.insert(std::make_pair(typeid(MyTemplateMatrix).name(), "MyTemplateMatrix")); types.insert(std::make_pair(typeid(MyTemplateMatrix).name(), "MyTemplateMatrix"));
types.insert(std::make_pair(typeid(ForwardKinematicsFactor).name(), "ForwardKinematicsFactor"));
mxArray *registry = mexGetVariable("global", "gtsamwrap_rttiRegistry"); mxArray *registry = mexGetVariable("global", "gtsamwrap_rttiRegistry");
if(!registry) 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); 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[]) 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: case 34:
MyTemplateMatrix_Level_34(nargout, out, nargin-1, in+1); MyTemplateMatrix_Level_34(nargout, out, nargin-1, in+1);
break; 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) { } catch(const std::exception& e) {
mexErrMsgTxt(("Exception from gtsam:\n" + std::string(e.what()) + "\n").c_str()); 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; static Collector_MyTemplatePoint2 collector_MyTemplatePoint2;
typedef std::set<boost::shared_ptr<MyTemplateMatrix>*> Collector_MyTemplateMatrix; typedef std::set<boost::shared_ptr<MyTemplateMatrix>*> Collector_MyTemplateMatrix;
static Collector_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; typedef std::set<boost::shared_ptr<ns1::ClassA>*> Collector_ns1ClassA;
static Collector_ns1ClassA collector_ns1ClassA; static Collector_ns1ClassA collector_ns1ClassA;
typedef std::set<boost::shared_ptr<ns1::ClassB>*> Collector_ns1ClassB; typedef std::set<boost::shared_ptr<ns1::ClassB>*> Collector_ns1ClassB;
@ -158,6 +160,12 @@ void _deleteAllObjects()
collector_MyTemplateMatrix.erase(iter++); collector_MyTemplateMatrix.erase(iter++);
anyDeleted = true; 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(); { for(Collector_ns1ClassA::iterator iter = collector_ns1ClassA.begin();
iter != collector_ns1ClassA.end(); ) { iter != collector_ns1ClassA.end(); ) {
delete *iter; delete *iter;
@ -209,6 +217,7 @@ void _namespaces_RTTIRegister() {
types.insert(std::make_pair(typeid(MyBase).name(), "MyBase")); types.insert(std::make_pair(typeid(MyBase).name(), "MyBase"));
types.insert(std::make_pair(typeid(MyTemplatePoint2).name(), "MyTemplatePoint2")); types.insert(std::make_pair(typeid(MyTemplatePoint2).name(), "MyTemplatePoint2"));
types.insert(std::make_pair(typeid(MyTemplateMatrix).name(), "MyTemplateMatrix")); types.insert(std::make_pair(typeid(MyTemplateMatrix).name(), "MyTemplateMatrix"));
types.insert(std::make_pair(typeid(ForwardKinematicsFactor).name(), "ForwardKinematicsFactor"));
mxArray *registry = mexGetVariable("global", "gtsamwrap_rttiRegistry"); mxArray *registry = mexGetVariable("global", "gtsamwrap_rttiRegistry");
if(!registry) if(!registry)

View File

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

View File

@ -55,11 +55,11 @@ PYBIND11_MODULE(class_py, m_) {
.def("create_ptrs",[](Test* self){return self->create_ptrs();}) .def("create_ptrs",[](Test* self){return self->create_ptrs();})
.def("create_MixedPtrs",[](Test* self){return self->create_MixedPtrs();}) .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("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__", .def("__repr__",
[](const Test &a) { [](const Test& self){
gtsam::RedirectCout redirect; gtsam::RedirectCout redirect;
a.print(); self.print();
return redirect.str(); return redirect.str();
}) })
.def("set_container",[](Test* self, std::vector<testing::Test> container){ self->set_container(container);}, py::arg("container")) .def("set_container",[](Test* self, std::vector<testing::Test> container){ self->set_container(container);}, py::arg("container"))
@ -83,7 +83,14 @@ PYBIND11_MODULE(class_py, m_) {
py::class_<MultipleTemplates<int, float>, std::shared_ptr<MultipleTemplates<int, float>>>(m_, "MultipleTemplatesIntFloat"); py::class_<MultipleTemplates<int, float>, std::shared_ptr<MultipleTemplates<int, float>>>(m_, "MultipleTemplatesIntFloat");
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("__repr__",
[](const MyFactor<gtsam::Pose2, gtsam::Matrix>& self, const string& s, const gtsam::KeyFormatter& keyFormatter){
gtsam::RedirectCout redirect;
self.print(s, keyFormatter);
return redirect.str();
}, py::arg("s") = "factor: ", py::arg("keyFormatter") = gtsam::DefaultKeyFormatter);
#include "python/specializations.h" #include "python/specializations.h"

View File

@ -30,6 +30,9 @@ PYBIND11_MODULE(functions_py, m_) {
m_.def("overloadedGlobalFunction",[](int a, double b){return ::overloadedGlobalFunction(a, b);}, py::arg("a"), py::arg("b")); m_.def("overloadedGlobalFunction",[](int a, double b){return ::overloadedGlobalFunction(a, b);}, py::arg("a"), py::arg("b"));
m_.def("MultiTemplatedFunctionStringSize_tDouble",[](const T& x, size_t y){return ::MultiTemplatedFunction<string,size_t,double>(x, y);}, py::arg("x"), py::arg("y")); m_.def("MultiTemplatedFunctionStringSize_tDouble",[](const T& x, size_t y){return ::MultiTemplatedFunction<string,size_t,double>(x, y);}, py::arg("x"), py::arg("y"));
m_.def("MultiTemplatedFunctionDoubleSize_tDouble",[](const T& x, size_t y){return ::MultiTemplatedFunction<double,size_t,double>(x, y);}, py::arg("x"), py::arg("y")); m_.def("MultiTemplatedFunctionDoubleSize_tDouble",[](const T& x, size_t y){return ::MultiTemplatedFunction<double,size_t,double>(x, y);}, py::arg("x"), py::arg("y"));
m_.def("DefaultFuncInt",[](int a){ ::DefaultFuncInt(a);}, py::arg("a") = 123);
m_.def("DefaultFuncString",[](const string& s){ ::DefaultFuncString(s);}, py::arg("s") = "hello");
m_.def("DefaultFuncObj",[](const gtsam::KeyFormatter& keyFormatter){ ::DefaultFuncObj(keyFormatter);}, py::arg("keyFormatter") = gtsam::DefaultKeyFormatter);
m_.def("TemplatedFunctionRot3",[](const gtsam::Rot3& t){ ::TemplatedFunction<Rot3>(t);}, py::arg("t")); m_.def("TemplatedFunctionRot3",[](const gtsam::Rot3& t){ ::TemplatedFunction<Rot3>(t);}, py::arg("t"));
#include "python/specializations.h" #include "python/specializations.h"

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("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")); .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" #include "python/specializations.h"

View File

@ -50,12 +50,14 @@ PYBIND11_MODULE(namespaces_py, m_) {
py::class_<ns2::ClassC, std::shared_ptr<ns2::ClassC>>(m_ns2, "ClassC") py::class_<ns2::ClassC, std::shared_ptr<ns2::ClassC>>(m_ns2, "ClassC")
.def(py::init<>()); .def(py::init<>());
m_ns2.attr("aNs2Var") = ns2::aNs2Var;
m_ns2.def("aGlobalFunction",[](){return ns2::aGlobalFunction();}); m_ns2.def("aGlobalFunction",[](){return ns2::aGlobalFunction();});
m_ns2.def("overloadedGlobalFunction",[](const ns1::ClassA& a){return ns2::overloadedGlobalFunction(a);}, py::arg("a")); m_ns2.def("overloadedGlobalFunction",[](const ns1::ClassA& a){return ns2::overloadedGlobalFunction(a);}, py::arg("a"));
m_ns2.def("overloadedGlobalFunction",[](const ns1::ClassA& a, double b){return ns2::overloadedGlobalFunction(a, b);}, py::arg("a"), py::arg("b")); m_ns2.def("overloadedGlobalFunction",[](const ns1::ClassA& a, double b){return ns2::overloadedGlobalFunction(a, b);}, py::arg("a"), py::arg("b"));
py::class_<ClassD, std::shared_ptr<ClassD>>(m_, "ClassD") py::class_<ClassD, std::shared_ptr<ClassD>>(m_, "ClassD")
.def(py::init<>()); .def(py::init<>());
m_.attr("aGlobalVar") = aGlobalVar;
#include "python/specializations.h" #include "python/specializations.h"

View File

@ -79,6 +79,8 @@ virtual class ns::OtherClass;
template<POSE, POINT> template<POSE, POINT>
class MyFactor { class MyFactor {
MyFactor(size_t key1, size_t key2, double measured, const gtsam::noiseModel::Base* noiseModel); MyFactor(size_t key1, size_t key2, double measured, const gtsam::noiseModel::Base* noiseModel);
void print(const string &s = "factor: ",
const gtsam::KeyFormatter &keyFormatter = gtsam::DefaultKeyFormatter);
}; };
// and a typedef specializing it // and a typedef specializing it

View File

@ -26,3 +26,8 @@ template<T>
void TemplatedFunction(const T& t); void TemplatedFunction(const T& t);
typedef TemplatedFunction<gtsam::Rot3> TemplatedFunctionRot3; typedef TemplatedFunction<gtsam::Rot3> TemplatedFunctionRot3;
// Check default arguments
void DefaultFuncInt(int a = 123);
void DefaultFuncString(const string& s = "hello");
void DefaultFuncObj(const gtsam::KeyFormatter& keyFormatter = gtsam::DefaultKeyFormatter);

View File

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

View File

@ -17,7 +17,7 @@ class ClassB {
// check namespace handling // check namespace handling
Vector aGlobalFunction(); Vector aGlobalFunction();
} } // namespace ns1
#include <path/to/ns2.h> #include <path/to/ns2.h>
namespace ns2 { namespace ns2 {
@ -38,7 +38,7 @@ class ClassB {
ClassB(); ClassB();
}; };
} } // namespace ns3
class ClassC { class ClassC {
ClassC(); ClassC();
@ -51,10 +51,12 @@ Vector aGlobalFunction();
ns1::ClassA overloadedGlobalFunction(const ns1::ClassA& a); ns1::ClassA overloadedGlobalFunction(const ns1::ClassA& a);
ns1::ClassA overloadedGlobalFunction(const ns1::ClassA& a, double b); ns1::ClassA overloadedGlobalFunction(const ns1::ClassA& a, double b);
} //\namespace ns2 int aNs2Var;
} // namespace ns2
class ClassD { class ClassD {
ClassD(); ClassD();
}; };
int aGlobalVar;

View File

@ -18,12 +18,10 @@ import unittest
sys.path.append(os.path.dirname(os.path.dirname(os.path.abspath(__file__)))) sys.path.append(os.path.dirname(os.path.dirname(os.path.abspath(__file__))))
from gtwrap.interface_parser import (ArgumentList, Class, Constructor, from gtwrap.interface_parser import (
ForwardDeclaration, GlobalFunction, ArgumentList, Class, Constructor, ForwardDeclaration, GlobalFunction,
Include, Method, Module, Namespace, Include, Method, Module, Namespace, Operator, ReturnType, StaticMethod,
Operator, ReturnType, StaticMethod, TemplatedType, Type, TypedefTemplateInstantiation, Typename, Variable)
TemplatedType, Type,
TypedefTemplateInstantiation, Typename)
class TestInterfaceParser(unittest.TestCase): class TestInterfaceParser(unittest.TestCase):
@ -179,6 +177,34 @@ class TestInterfaceParser(unittest.TestCase):
self.assertEqual("vector<boost::shared_ptr<T>>", self.assertEqual("vector<boost::shared_ptr<T>>",
args_list[1].ctype.to_cpp(True)) args_list[1].ctype.to_cpp(True))
def test_default_arguments(self):
"""Tests any expression that is a valid default argument"""
args = ArgumentList.rule.parseString(
"string s=\"hello\", int a=3, "
"int b, double pi = 3.1415, "
"gtsam::KeyFormatter kf = gtsam::DefaultKeyFormatter, "
"std::vector<size_t> p = std::vector<size_t>(), "
"std::vector<size_t> l = (1, 2, 'name', \"random\", 3.1415)"
)[0].args_list
# Test for basic types
self.assertEqual(args[0].default, "hello")
self.assertEqual(args[1].default, 3)
# '' is falsy so we can check against it
self.assertEqual(args[2].default, '')
self.assertFalse(args[2].default)
self.assertEqual(args[3].default, 3.1415)
# Test non-basic type
self.assertEqual(repr(args[4].default.typename),
'gtsam::DefaultKeyFormatter')
# Test templated type
self.assertEqual(repr(args[5].default.typename), 'std::vector<size_t>')
# Test for allowing list as default argument
print(args)
self.assertEqual(args[6].default, (1, 2, 'name', "random", 3.1415))
def test_return_type(self): def test_return_type(self):
"""Test ReturnType""" """Test ReturnType"""
# Test void # Test void
@ -388,6 +414,16 @@ class TestInterfaceParser(unittest.TestCase):
ret.parent_class.namespaces) ret.parent_class.namespaces)
self.assertTrue(ret.is_virtual) 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): def test_include(self):
"""Test for include statements.""" """Test for include statements."""
include = Include.rule.parseString( include = Include.rule.parseString(
@ -413,6 +449,23 @@ class TestInterfaceParser(unittest.TestCase):
self.assertEqual("Values", func.return_type.type1.typename.name) self.assertEqual("Values", func.return_type.type1.typename.name)
self.assertEqual(3, len(func.args)) self.assertEqual(3, len(func.args))
def test_global_variable(self):
"""Test for global variable."""
variable = Variable.rule.parseString("string kGravity;")[0]
self.assertEqual(variable.name, "kGravity")
self.assertEqual(variable.ctype.typename.name, "string")
variable = Variable.rule.parseString("string kGravity = 9.81;")[0]
self.assertEqual(variable.name, "kGravity")
self.assertEqual(variable.ctype.typename.name, "string")
self.assertEqual(variable.default, 9.81)
variable = Variable.rule.parseString("const string kGravity = 9.81;")[0]
self.assertEqual(variable.name, "kGravity")
self.assertEqual(variable.ctype.typename.name, "string")
self.assertTrue(variable.ctype.is_const)
self.assertEqual(variable.default, 9.81)
def test_namespace(self): def test_namespace(self):
"""Test for namespace parsing.""" """Test for namespace parsing."""
namespace = Namespace.rule.parseString(""" namespace = Namespace.rule.parseString("""
@ -469,16 +522,19 @@ class TestInterfaceParser(unittest.TestCase):
}; };
} }
int oneVar;
} }
class Global{ class Global{
}; };
int globalVar;
""") """)
# print("module: ", module) # print("module: ", module)
# print(dir(module.content[0].name)) # print(dir(module.content[0].name))
self.assertEqual(["one", "Global"], [x.name for x in module.content]) self.assertEqual(["one", "Global", "globalVar"],
self.assertEqual(["two", "two_dummy", "two"], [x.name for x in module.content])
self.assertEqual(["two", "two_dummy", "two", "oneVar"],
[x.name for x in module.content[0].content]) [x.name for x in module.content[0].content])