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 List, Sequence, Union
17 from pyparsing
import ParseResults
18 from pyparsing
import Forward, Optional, Or, delimitedList
20 from .tokens
import (BASIC_TYPES, CONST, IDENT, LOPBRACK, RAW_POINTER, REF,
21 ROPBRACK, SHARED_POINTER)
26 Class which holds a type's name, full namespace, and template arguments. 30 gtsam::PinholeCamera<gtsam::Cal3S2> 33 will give the name as `PinholeCamera`, namespace as `gtsam`, 34 and template instantiations as `[gtsam::Cal3S2]`. 37 namespaces_and_name: A list representing the namespaces of the type 38 with the type being the last element. 39 instantiations: Template parameters to the type. 42 namespaces_name_rule = delimitedList(IDENT,
"::")
43 instantiation_name_rule = delimitedList(IDENT,
"::")
46 ).setParseAction(
lambda t:
Typename(t))
50 instantiations: Sequence[ParseResults] = ()):
71 """Unpack the parsed result to get the Typename instance.""" 72 return parse_result[0]
78 """Get the instantiated name of the type.""" 81 res += instantiation.instantiated_name()
85 """Return the fully qualified name, e.g. `gtsam::internal::PoseKey`.""" 89 """Generate the C++ code for wrapping.""" 91 cpp_name = self.
name +
"<{}>".
format(
", ".join(
103 return str(self) ==
str(other)
114 Basic types are the fundamental built-in types in C++ such as double, int, char, etc. 116 When using templates, the basic type will take on the same form as the template. 120 template<T = {double}> 121 void func(const T& x); 127 m_.def("funcDouble",[](const double& x){ 133 rule = (Or(BASIC_TYPES)(
"typename")).setParseAction(
lambda t:
BasicType(t))
141 Custom defined types with the namespace. 142 Essentially any C++ data type that is not a BasicType. 149 Here `gtsam::Matrix` is a custom type. 152 rule = (Typename.rule(
"typename")).setParseAction(
lambda t:
CustomType(t))
160 Parsed datatype, can be either a fundamental/basic type or a custom datatype. 161 E.g. void, double, size_t, Matrix. 162 Think of this as a high-level type which encodes the typename and other 163 characteristics of the type. 165 The type can optionally be a raw pointer, shared pointer or reference. 166 Can also be optionally qualified with a `const`, e.g. `const int`. 169 Optional(
CONST(
"is_const"))
170 + (BasicType.rule(
"basic") | CustomType.rule(
"qualified"))
174 ).setParseAction(
lambda t: Type.from_parse_result(t))
176 def __init__(self, typename: Typename, is_const: str, is_shared_ptr: str,
177 is_ptr: str, is_ref: str, is_basic: bool):
187 """Return the resulting Type from parsing the source.""" 191 typename=t.basic.typename,
193 is_shared_ptr=t.is_shared_ptr,
200 typename=t.qualified.typename,
202 is_shared_ptr=t.is_shared_ptr,
208 raise ValueError(
"Parse result is not a Type")
213 return "{is_const}{self.typename}{is_ptr_or_ref}".
format(
215 is_const=
"const " if self.
is_const else "",
216 is_ptr_or_ref=
" " + is_ptr_or_ref
if is_ptr_or_ref
else "")
220 Generate the C++ code for wrapping. 222 Treat all pointers as "const shared_ptr<T>&" 223 Treat Matrix and Vector as "const Matrix&" and "const Vector&" resp. 227 typename =
"std::shared_ptr<{typename}>".
format(
232 typename = typename =
"{typename}&".
format(
237 return (
"{const}{typename}".
format(
240 or self.
typename.name
in [
"Matrix",
"Vector"])
else "",
244 """Convenience method to get the typename of this type.""" 250 Parser rule for data types which are templated. 251 This is done so that the template parameters can be pointers/references. 253 E.g. std::vector<double>, BearingRange<Pose3, Point3> 258 Optional(
CONST(
"is_const"))
259 + Typename.rule(
"typename")
262 + delimitedList(Type.rule ^ rule,
",")(
"template_params")
267 ).setParseAction(
lambda t: TemplatedType.from_parse_result(t))
269 def __init__(self, typename: Typename, template_params: List[Type],
270 is_const: str, is_shared_ptr: str, is_ptr: str, is_ref: str):
271 instantiations = [param.typename
for param
in template_params]
285 """Get the TemplatedType from the parser results.""" 286 return TemplatedType(t.typename, t.template_params, t.is_const,
287 t.is_shared_ptr, t.is_ptr, t.is_ref)
290 return "TemplatedType({typename.namespaces}::{typename.name})".
format(
295 Generate the C++ code for wrapping. 300 typename =
"{typename}<{template_args}>".
format(
301 typename=self.
typename.qualified_name(),
302 template_args=template_args)
305 typename = f
"std::shared_ptr<{typename}>" 307 typename =
"{typename}*".
format(typename=typename)
309 typename = typename =
"{typename}&".
format(typename=typename)
313 return (
"{const}{typename}".
format(
316 or self.
typename.name
in [
"Matrix",
"Vector"])
else "",
bool isinstance(handle obj)
def instantiated_name(self)
std::string format(const std::string &str, const std::vector< std::string > &find, const std::vector< std::string > &replace)