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] = ()):
 
   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.""" 
   88             cpp_name = self.
name + 
"<{}>".
format(
", ".join(
 
  100             return str(self) == 
str(other)
 
  111     Basic types are the fundamental built-in types in C++ such as double, int, char, etc. 
  113     When using templates, the basic type will take on the same form as the template. 
  117     template<T = {double}> 
  118     void func(const T& x); 
  124     m_.def("funcDouble",[](const double& x){ 
  130     rule = (Or(BASIC_TYPES)(
"typename")).setParseAction(
lambda t: 
BasicType(t))
 
  138     Custom defined types with the namespace. 
  139     Essentially any C++ data type that is not a BasicType. 
  146     Here `gtsam::Matrix` is a custom type. 
  149     rule = (Typename.rule(
"typename")).setParseAction(
lambda t: 
CustomType(t))
 
  157     Parsed datatype, can be either a fundamental/basic type or a custom datatype. 
  158     E.g. void, double, size_t, Matrix. 
  159     Think of this as a high-level type which encodes the typename and other 
  160     characteristics of the type. 
  162     The type can optionally be a raw pointer, shared pointer or reference. 
  163     Can also be optionally qualified with a `const`, e.g. `const int`. 
  166         Optional(
CONST(
"is_const"))  
 
  167         + (BasicType.rule(
"basic") | CustomType.rule(
"qualified"))  
 
  171     ).setParseAction(
lambda t: Type.from_parse_result(t))
 
  173     def __init__(self, typename: Typename, is_const: str, is_shared_ptr: str,
 
  174                  is_ptr: str, is_ref: str, is_basic: bool):
 
  184         """Return the resulting Type from parsing the source.""" 
  188                 typename=t.basic.typename,
 
  190                 is_shared_ptr=t.is_shared_ptr,
 
  197                 typename=t.qualified.typename,
 
  199                 is_shared_ptr=t.is_shared_ptr,
 
  205             raise ValueError(
"Parse result is not a Type")
 
  210         return "{is_const}{self.typename}{is_ptr_or_ref}".
format(
 
  212             is_const=
"const " if self.
is_const else "",
 
  213             is_ptr_or_ref=
" " + is_ptr_or_ref 
if is_ptr_or_ref 
else "")
 
  217         Generate the C++ code for wrapping. 
  219         Treat all pointers as "const shared_ptr<T>&" 
  223             typename = 
"std::shared_ptr<{typename}>".
format(
 
  228             typename = typename = 
"{typename}&".
format(
 
  233         return (
"{const}{typename}".
format(
 
  234             const=
"const " if self.
is_const else "", typename=typename))
 
  237         """Convenience method to get the typename of this type.""" 
  243     Parser rule for data types which are templated. 
  244     This is done so that the template parameters can be pointers/references. 
  246     E.g. std::vector<double>, BearingRange<Pose3, Point3> 
  251         Optional(
CONST(
"is_const"))  
 
  252         + Typename.rule(
"typename")  
 
  255             + delimitedList(Type.rule ^ rule, 
",")(
"template_params")  
 
  260     ).setParseAction(
lambda t: TemplatedType.from_parse_result(t))
 
  262     def __init__(self, typename: Typename, template_params: List[Type],
 
  263                  is_const: str, is_shared_ptr: str, is_ptr: str, is_ref: str):
 
  264         instantiations = [param.typename 
for param 
in template_params]
 
  278         """Get the TemplatedType from the parser results.""" 
  279         return TemplatedType(t.typename, t.template_params, t.is_const,
 
  280                              t.is_shared_ptr, t.is_ptr, t.is_ref)
 
  283         return "TemplatedType({typename.namespaces}::{typename.name})".
format(
 
  288         Generate the C++ code for wrapping. 
  293         typename = 
"{typename}<{template_args}>".
format(
 
  294             typename=self.
typename.qualified_name(),
 
  295             template_args=template_args)
 
  298             typename = f
"std::shared_ptr<{typename}>" 
  300             typename = 
"{typename}*".
format(typename=typename)
 
  302             typename = typename = 
"{typename}&".
format(typename=typename)
 
  306         return (
"{const}{typename}".
format(
 
  307             const=
"const " if self.
is_const else "", typename=typename))