Saving before restoring
parent
5bcd5d3c89
commit
0dcd102f5e
|
@ -152,24 +152,14 @@ void Module::parseMarkup(const std::string& data) {
|
|||
'<' >> basic.name_p[push_back_a(cls.templateArgs)] >> *(',' >> basic.name_p[push_back_a(cls.templateArgs)]) >>
|
||||
'>');
|
||||
|
||||
// NOTE: allows for pointers to all types
|
||||
// Slightly more permissive than before on basis/eigen type qualification
|
||||
// Argument list
|
||||
ArgumentList args;
|
||||
Argument arg0, arg;
|
||||
TypeGrammar argument_type_g(arg.type);
|
||||
Rule argument_p =
|
||||
!str_p("const")[assign_a(arg.is_const, true)]
|
||||
>> argument_type_g
|
||||
>> (!ch_p('&')[assign_a(arg.is_ref, true)] | !ch_p('*')[assign_a(arg.is_ptr, true)])
|
||||
[push_back_a(args, arg)]
|
||||
[assign_a(arg,arg0)];
|
||||
|
||||
Rule argumentList_p = !argument_p >> * (',' >> argument_p);
|
||||
ArgumentListGrammar argumentlist_g(args);
|
||||
|
||||
// parse class constructor
|
||||
Constructor constructor0(verbose), constructor(verbose);
|
||||
Rule constructor_p =
|
||||
(basic.className_p >> '(' >> argumentList_p >> ')' >> ';' >> !basic.comments_p)
|
||||
(basic.className_p >> '(' >> argumentlist_g >> ')' >> ';' >> !basic.comments_p)
|
||||
[bl::bind(&Constructor::push_back, bl::var(constructor), bl::var(args))]
|
||||
[clear_a(args)];
|
||||
|
||||
|
@ -194,7 +184,7 @@ void Module::parseMarkup(const std::string& data) {
|
|||
Rule method_p =
|
||||
!templateArgValues_p >>
|
||||
(returnValue_p >> methodName_p[assign_a(methodName)] >>
|
||||
'(' >> argumentList_p >> ')' >>
|
||||
'(' >> argumentlist_g >> ')' >>
|
||||
!str_p("const")[assign_a(isConst,true)] >> ';' >> *basic.comments_p)
|
||||
[bl::bind(&Class::addMethod, bl::var(cls), verbose, bl::var(isConst),
|
||||
bl::var(methodName), bl::var(args), bl::var(retVal),
|
||||
|
@ -208,7 +198,7 @@ void Module::parseMarkup(const std::string& data) {
|
|||
|
||||
Rule static_method_p =
|
||||
(str_p("static") >> returnValue_p >> staticMethodName_p[assign_a(methodName)] >>
|
||||
'(' >> argumentList_p >> ')' >> ';' >> *basic.comments_p)
|
||||
'(' >> argumentlist_g >> ')' >> ';' >> *basic.comments_p)
|
||||
[bl::bind(&StaticMethod::addOverload,
|
||||
bl::var(cls.static_methods)[bl::var(methodName)],
|
||||
bl::var(methodName), bl::var(args), bl::var(retVal), Qualified(),verbose)]
|
||||
|
@ -248,7 +238,7 @@ void Module::parseMarkup(const std::string& data) {
|
|||
Qualified globalFunction;
|
||||
Rule global_function_p =
|
||||
(returnValue_p >> staticMethodName_p[assign_a(globalFunction.name_)] >>
|
||||
'(' >> argumentList_p >> ')' >> ';' >> *basic.comments_p)
|
||||
'(' >> argumentlist_g >> ')' >> ';' >> *basic.comments_p)
|
||||
[assign_a(globalFunction.namespaces_,namespaces)]
|
||||
[bl::bind(&GlobalFunction::addOverload,
|
||||
bl::var(global_functions)[bl::var(globalFunction.name_)],
|
||||
|
@ -323,8 +313,7 @@ void Module::parseMarkup(const std::string& data) {
|
|||
printf("parsing stopped at \n%.20s\n",info.stop);
|
||||
cout << "Stopped near:\n"
|
||||
"class '" << cls.name() << "'\n"
|
||||
"method '" << methodName << "'\n"
|
||||
"argument '" << arg.name << "'" << endl;
|
||||
"method '" << methodName << endl;
|
||||
throw ParseFailed((int)info.length);
|
||||
}
|
||||
|
||||
|
|
|
@ -1,4 +1,4 @@
|
|||
// comments!
|
||||
// comments!
|
||||
|
||||
class VectorNotEigen;
|
||||
class ns::OtherClass;
|
||||
|
@ -7,128 +7,126 @@ namespace gtsam {
|
|||
|
||||
class Point2 {
|
||||
Point2();
|
||||
// Point2(double x, double y);
|
||||
Point2(double x, double y);
|
||||
double x() const;
|
||||
// double y() const;
|
||||
// int dim() const;
|
||||
// char returnChar() const;
|
||||
// void argChar(char a) const;
|
||||
// void argUChar(unsigned char a) const;
|
||||
// void eigenArguments(Vector v, Matrix m) const;
|
||||
// VectorNotEigen vectorConfusion();
|
||||
//
|
||||
// void serializable() const; // Sets flag and creates export, but does not make serialization functions
|
||||
double y() const;
|
||||
int dim() const;
|
||||
char returnChar() const;
|
||||
void argChar(char a) const;
|
||||
void argUChar(unsigned char a) const;
|
||||
void eigenArguments(Vector v, Matrix m) const;
|
||||
VectorNotEigen vectorConfusion();
|
||||
|
||||
void serializable() const; // Sets flag and creates export, but does not make serialization functions
|
||||
};
|
||||
|
||||
} // end namespace should be removed
|
||||
class Point3 {
|
||||
Point3(double x, double y, double z);
|
||||
double norm() const;
|
||||
|
||||
//class Point3 {
|
||||
// Point3(double x, double y, double z);
|
||||
// double norm() const;
|
||||
//
|
||||
// // static functions - use static keyword and uppercase
|
||||
// static double staticFunction();
|
||||
// static gtsam::Point3 StaticFunctionRet(double z);
|
||||
//
|
||||
// // enabling serialization functionality
|
||||
// void serialize() const; // Just triggers a flag internally and removes actual function
|
||||
//};
|
||||
//
|
||||
//}
|
||||
//// another comment
|
||||
//
|
||||
//// another comment
|
||||
//
|
||||
///**
|
||||
// * A multi-line comment!
|
||||
// */
|
||||
//
|
||||
//// An include! Can go anywhere outside of a class, in any order
|
||||
//#include <folder/path/to/Test.h>
|
||||
//
|
||||
//class Test {
|
||||
//
|
||||
// /* a comment! */
|
||||
// // another comment
|
||||
// Test();
|
||||
//
|
||||
// pair<Vector,Matrix> return_pair (Vector v, Matrix A) const; // intentionally the first method
|
||||
//
|
||||
// bool return_bool (bool value) const; // comment after a line!
|
||||
// size_t return_size_t (size_t value) const;
|
||||
// int return_int (int value) const;
|
||||
// double return_double (double value) const;
|
||||
//
|
||||
// Test(double a, Matrix b); // a constructor in the middle of a class
|
||||
//
|
||||
// // comments in the middle!
|
||||
//
|
||||
// // (more) comments in the middle!
|
||||
//
|
||||
// string return_string (string value) const;
|
||||
// Vector return_vector1(Vector value) const;
|
||||
// Matrix return_matrix1(Matrix value) const;
|
||||
// Vector return_vector2(Vector value) const;
|
||||
// Matrix return_matrix2(Matrix value) const;
|
||||
// void arg_EigenConstRef(const Matrix& value) const;
|
||||
//
|
||||
// bool return_field(const Test& t) const;
|
||||
//
|
||||
// Test* return_TestPtr(Test* value) const;
|
||||
// Test return_Test(Test* value) const;
|
||||
//
|
||||
// gtsam::Point2* return_Point2Ptr(bool value) const;
|
||||
//
|
||||
// pair<Test*,Test*> create_ptrs () const;
|
||||
// pair<Test ,Test*> create_MixedPtrs () const;
|
||||
// pair<Test*,Test*> return_ptrs (Test* p1, Test* p2) const;
|
||||
//
|
||||
// void print() const;
|
||||
//
|
||||
// // comments at the end!
|
||||
//
|
||||
// // even more comments at the end!
|
||||
//};
|
||||
//
|
||||
//
|
||||
//Vector aGlobalFunction();
|
||||
//
|
||||
//// An overloaded global function
|
||||
//Vector overloadedGlobalFunction(int a);
|
||||
//Vector overloadedGlobalFunction(int a, double b);
|
||||
//
|
||||
//// A base class
|
||||
//virtual class MyBase {
|
||||
//
|
||||
//};
|
||||
//
|
||||
//// A templated class
|
||||
//template<T = {gtsam::Point2, gtsam::Point3}>
|
||||
//virtual class MyTemplate : MyBase {
|
||||
// MyTemplate();
|
||||
//
|
||||
// template<ARG = {gtsam::Point2, gtsam::Point3, Vector, Matrix}>
|
||||
// void templatedMethod(const ARG& t);
|
||||
//
|
||||
// // Stress test templates and pointer combinations
|
||||
// void accept_T(const T& value) const;
|
||||
// void accept_Tptr(T* value) const;
|
||||
// T* return_Tptr(T* value) const;
|
||||
// T return_T(T* value) const;
|
||||
// pair<T*,T*> create_ptrs () const;
|
||||
// pair<T ,T*> create_MixedPtrs () const;
|
||||
// pair<T*,T*> return_ptrs (T* p1, T* p2) const;
|
||||
//};
|
||||
//
|
||||
//// A doubly templated class
|
||||
//template<POSE, POINT>
|
||||
//class MyFactor {
|
||||
// MyFactor(size_t key1, size_t key2, double measured, const gtsam::noiseModel::Base* noiseModel);
|
||||
//};
|
||||
//
|
||||
//// and a typedef specializing it
|
||||
//typedef MyFactor<gtsam::Pose2, Matrix> MyFactorPosePoint2;
|
||||
//
|
||||
//// comments at the end!
|
||||
//
|
||||
//// even more comments at the end!
|
||||
// static functions - use static keyword and uppercase
|
||||
static double staticFunction();
|
||||
static gtsam::Point3 StaticFunctionRet(double z);
|
||||
|
||||
// enabling serialization functionality
|
||||
void serialize() const; // Just triggers a flag internally and removes actual function
|
||||
};
|
||||
|
||||
}
|
||||
// another comment
|
||||
|
||||
// another comment
|
||||
|
||||
/**
|
||||
* A multi-line comment!
|
||||
*/
|
||||
|
||||
// An include! Can go anywhere outside of a class, in any order
|
||||
#include <folder/path/to/Test.h>
|
||||
|
||||
class Test {
|
||||
|
||||
/* a comment! */
|
||||
// another comment
|
||||
Test();
|
||||
|
||||
pair<Vector,Matrix> return_pair (Vector v, Matrix A) const; // intentionally the first method
|
||||
|
||||
bool return_bool (bool value) const; // comment after a line!
|
||||
size_t return_size_t (size_t value) const;
|
||||
int return_int (int value) const;
|
||||
double return_double (double value) const;
|
||||
|
||||
Test(double a, Matrix b); // a constructor in the middle of a class
|
||||
|
||||
// comments in the middle!
|
||||
|
||||
// (more) comments in the middle!
|
||||
|
||||
string return_string (string value) const;
|
||||
Vector return_vector1(Vector value) const;
|
||||
Matrix return_matrix1(Matrix value) const;
|
||||
Vector return_vector2(Vector value) const;
|
||||
Matrix return_matrix2(Matrix value) const;
|
||||
void arg_EigenConstRef(const Matrix& value) const;
|
||||
|
||||
bool return_field(const Test& t) const;
|
||||
|
||||
Test* return_TestPtr(Test* value) const;
|
||||
Test return_Test(Test* value) const;
|
||||
|
||||
gtsam::Point2* return_Point2Ptr(bool value) const;
|
||||
|
||||
pair<Test*,Test*> create_ptrs () const;
|
||||
pair<Test ,Test*> create_MixedPtrs () const;
|
||||
pair<Test*,Test*> return_ptrs (Test* p1, Test* p2) const;
|
||||
|
||||
void print() const;
|
||||
|
||||
// comments at the end!
|
||||
|
||||
// even more comments at the end!
|
||||
};
|
||||
|
||||
|
||||
Vector aGlobalFunction();
|
||||
|
||||
// An overloaded global function
|
||||
Vector overloadedGlobalFunction(int a);
|
||||
Vector overloadedGlobalFunction(int a, double b);
|
||||
|
||||
// A base class
|
||||
virtual class MyBase {
|
||||
|
||||
};
|
||||
|
||||
// A templated class
|
||||
template<T = {gtsam::Point2, gtsam::Point3}>
|
||||
virtual class MyTemplate : MyBase {
|
||||
MyTemplate();
|
||||
|
||||
template<ARG = {gtsam::Point2, gtsam::Point3, Vector, Matrix}>
|
||||
void templatedMethod(const ARG& t);
|
||||
|
||||
// Stress test templates and pointer combinations
|
||||
void accept_T(const T& value) const;
|
||||
void accept_Tptr(T* value) const;
|
||||
T* return_Tptr(T* value) const;
|
||||
T return_T(T* value) const;
|
||||
pair<T*,T*> create_ptrs () const;
|
||||
pair<T ,T*> create_MixedPtrs () const;
|
||||
pair<T*,T*> return_ptrs (T* p1, T* p2) const;
|
||||
};
|
||||
|
||||
// A doubly templated class
|
||||
template<POSE, POINT>
|
||||
class MyFactor {
|
||||
MyFactor(size_t key1, size_t key2, double measured, const gtsam::noiseModel::Base* noiseModel);
|
||||
};
|
||||
|
||||
// and a typedef specializing it
|
||||
typedef MyFactor<gtsam::Pose2, Matrix> MyFactorPosePoint2;
|
||||
|
||||
// comments at the end!
|
||||
|
||||
// even more comments at the end!
|
||||
|
|
Loading…
Reference in New Issue