2 GTSAM Copyright 2010-2020, Georgia Tech Research Corporation, 3 Atlanta, Georgia 30332-0415 6 See LICENSE for the license information 8 Define the parser rules and classes for various C++ types. 10 Author: Duy Nguyen Ta, Fan Jiang, Matthew Sklar, Varun Agrawal, and Frank Dellaert 15 from typing
import Iterable, List, Union
17 from pyparsing
import Forward, Optional, Or, ParseResults, delimitedList
19 from .tokens
import (BASIS_TYPES, CONST, IDENT, LOPBRACK, RAW_POINTER, REF,
20 ROPBRACK, SHARED_POINTER)
25 Generic type which can be either a basic type or a class type, 26 similar to C++'s `typename` aka a qualified dependent type. 27 Contains type name with full namespace and template arguments. 31 gtsam::PinholeCamera<gtsam::Cal3S2> 34 will give the name as `PinholeCamera`, namespace as `gtsam`, 35 and template instantiations as `[gtsam::Cal3S2]`. 38 namespaces_and_name: A list representing the namespaces of the type 39 with the type being the last element. 40 instantiations: Template parameters to the type. 43 namespaces_name_rule = delimitedList(IDENT,
"::")
44 instantiation_name_rule = delimitedList(IDENT,
"::")
47 ).setParseAction(
lambda t:
Typename(t))
51 instantiations: Union[tuple, list, str, ParseResults] = ()):
68 """Unpack the parsed result to get the Typename instance.""" 69 return parse_result[0]
75 """Get the instantiated name of the type.""" 78 res += instantiation.instantiated_name()
82 """Return the fully qualified name, e.g. `gtsam::internal::PoseKey`.""" 86 """Generate the C++ code for wrapping.""" 89 cpp_name = self.
name +
"<{}>".format(
", ".join(
93 return '{}{}{}'.format(
101 return str(self) ==
str(other)
112 Basic types are the fundamental built-in types in C++ such as double, int, char, etc. 114 When using templates, the basis type will take on the same form as the template. 118 template<T = {double}> 119 void func(const T& x); 125 m_.def("CoolFunctionDoubleDouble",[](const double& s) { 126 return wrap_example::CoolFunction<double,double>(s); 131 rule = (Or(BASIS_TYPES)(
"typename")).setParseAction(
lambda t:
BasicType(t))
139 Custom defined types with the namespace. 140 Essentially any C++ data type that is not a BasicType. 147 Here `gtsam::Matrix` is a custom type. 150 rule = (Typename.rule(
"typename")).setParseAction(
lambda t:
CustomType(t))
158 Parsed datatype, can be either a fundamental type or a custom datatype. 159 E.g. void, double, size_t, Matrix. 161 The type can optionally be a raw pointer, shared pointer or reference. 162 Can also be optionally qualified with a `const`, e.g. `const int`. 165 Optional(
CONST(
"is_const"))
166 + (BasicType.rule(
"basis") | CustomType.rule(
"qualified"))
170 ).setParseAction(
lambda t: Type.from_parse_result(t))
172 def __init__(self, typename: Typename, is_const: str, is_shared_ptr: str,
173 is_ptr: str, is_ref: str, is_basic: bool):
183 """Return the resulting Type from parsing the source.""" 186 typename=t.basis.typename,
188 is_shared_ptr=t.is_shared_ptr,
195 typename=t.qualified.typename,
197 is_shared_ptr=t.is_shared_ptr,
203 raise ValueError(
"Parse result is not a Type")
208 return "{is_const}{self.typename}{is_ptr_or_ref}".format(
210 is_const=
"const " if self.
is_const else "",
211 is_ptr_or_ref=
" " + is_ptr_or_ref
if is_ptr_or_ref
else "")
213 def to_cpp(self, use_boost: bool) -> str:
215 Generate the C++ code for wrapping. 217 Treat all pointers as "const shared_ptr<T>&" 218 Treat Matrix and Vector as "const Matrix&" and "const Vector&" resp. 221 use_boost: Flag indicating whether to use boost::shared_ptr or std::shared_ptr. 223 shared_ptr_ns =
"boost" if use_boost
else "std" 226 typename =
"{ns}::shared_ptr<{typename}>".format(
227 ns=shared_ptr_ns, typename=self.typename.to_cpp())
229 typename =
"{typename}*".format(typename=self.typename.to_cpp())
230 elif self.
is_ref or self.typename.name
in [
"Matrix",
"Vector"]:
231 typename = typename =
"{typename}&".format(
232 typename=self.typename.to_cpp())
234 typename = self.typename.to_cpp()
236 return (
"{const}{typename}".format(
239 or self.typename.name
in [
"Matrix",
"Vector"])
else "",
245 Parser rule for data types which are templated. 246 This is done so that the template parameters can be pointers/references. 248 E.g. std::vector<double>, BearingRange<Pose3, Point3> 253 Optional(
CONST(
"is_const"))
254 + Typename.rule(
"typename")
257 + delimitedList(Type.rule ^ rule,
",")(
"template_params")
262 ).setParseAction(
lambda t: TemplatedType.from_parse_result(t))
264 def __init__(self, typename: Typename, template_params: List[Type],
265 is_const: str, is_shared_ptr: str, is_ptr: str, is_ref: str):
266 instantiations = [param.typename
for param
in template_params]
280 """Get the TemplatedType from the parser results.""" 281 return TemplatedType(t.typename, t.template_params, t.is_const,
282 t.is_shared_ptr, t.is_ptr, t.is_ref)
285 return "TemplatedType({typename.namespaces}::{typename.name})".format(
290 Generate the C++ code for wrapping. 293 use_boost: Flag indicating whether to use boost::shared_ptr or std::shared_ptr. 296 template_args =
", ".join(
299 typename =
"{typename}<{template_args}>".format(
300 typename=self.typename.qualified_name(),
301 template_args=template_args)
303 shared_ptr_ns =
"boost" if use_boost
else "std" 305 typename =
"{ns}::shared_ptr<{typename}>".format(ns=shared_ptr_ns,
308 typename =
"{typename}*".format(typename=typename)
309 elif self.
is_ref or self.typename.name
in [
"Matrix",
"Vector"]:
310 typename = typename =
"{typename}&".format(typename=typename)
314 return (
"{const}{typename}".format(
317 or self.typename.name
in [
"Matrix",
"Vector"])
else "",
bool isinstance(handle obj)
def instantiated_name(self)