Simplified include handling in wrap: no more default includes, includes are not associated with a class or a namespace.

release/4.3a0
Alex Cunningham 2012-07-17 18:30:02 +00:00
parent 4bcc974cae
commit 4b772b43cf
12 changed files with 37 additions and 77 deletions

26
gtsam.h
View File

@ -46,11 +46,9 @@
* - To use a namespace (e.g., generate a "using namespace x" line in cpp files), add "using namespace x;"
* - This declaration applies to all classes *after* the declaration, regardless of brackets
* Includes in C++ wrappers
* - By default, the include will be <[classname].h>
* - All namespaces must have angle brackets: <path>
* - To override, add a full include statement just before the class statement
* - An override include can be added for a namespace by placing it just before the namespace statement
* - Both classes and namespace accept exactly one namespace
* - All includes will be collected and added in a single file
* - All namespaces must have angle brackets: <path>
* - No default includes will be added
* Using classes defined in other modules
* - If you are using a class 'OtherClass' not wrapped in this definition file, add "class OtherClass;" to avoid a dependency error
* Virtual inheritance
@ -98,6 +96,7 @@ virtual class Value {
size_t dim() const;
};
#include <gtsam/base/LieVector.h>
virtual class LieVector : gtsam::Value {
// Standard constructors
LieVector();
@ -126,6 +125,7 @@ virtual class LieVector : gtsam::Value {
static Vector Logmap(const gtsam::LieVector& p);
};
#include <gtsam/base/LieMatrix.h>
virtual class LieMatrix : gtsam::Value {
// Standard constructors
LieMatrix();
@ -472,6 +472,7 @@ virtual class Cal3_S2 : gtsam::Value {
Matrix matrix_inverse() const;
};
#include <gtsam/geometry/Cal3DS2.h>
virtual class Cal3DS2 : gtsam::Value {
// Standard Constructors
Cal3DS2();
@ -715,6 +716,7 @@ class SymbolicFactorGraph {
//FastSet<Index> keys() const;
};
#include <gtsam/inference/SymbolicSequentialSolver.h>
class SymbolicSequentialSolver {
// Standard Constructors and Named Constructors
SymbolicSequentialSolver(const gtsam::SymbolicFactorGraph& factorGraph);
@ -728,6 +730,7 @@ class SymbolicSequentialSolver {
gtsam::SymbolicBayesNet* eliminate() const;
};
#include <gtsam/inference/SymbolicMultifrontalSolver.h>
class SymbolicMultifrontalSolver {
// Standard Constructors and Named Constructors
SymbolicMultifrontalSolver(const gtsam::SymbolicFactorGraph& factorGraph);
@ -776,7 +779,6 @@ namespace noiseModel {
virtual class Base {
};
#include <gtsam/linear/NoiseModel.h>
virtual class Gaussian : gtsam::noiseModel::Base {
static gtsam::noiseModel::Gaussian* SqrtInformation(Matrix R);
static gtsam::noiseModel::Gaussian* Covariance(Matrix R);
@ -784,7 +786,6 @@ virtual class Gaussian : gtsam::noiseModel::Base {
void print(string s) const;
};
#include <gtsam/linear/NoiseModel.h>
virtual class Diagonal : gtsam::noiseModel::Gaussian {
static gtsam::noiseModel::Diagonal* Sigmas(Vector sigmas);
static gtsam::noiseModel::Diagonal* Variances(Vector variances);
@ -793,7 +794,6 @@ virtual class Diagonal : gtsam::noiseModel::Gaussian {
void print(string s) const;
};
#include <gtsam/linear/NoiseModel.h>
virtual class Isotropic : gtsam::noiseModel::Diagonal {
static gtsam::noiseModel::Isotropic* Sigma(size_t dim, double sigma);
static gtsam::noiseModel::Isotropic* Variance(size_t dim, double varianace);
@ -801,14 +801,13 @@ virtual class Isotropic : gtsam::noiseModel::Diagonal {
void print(string s) const;
};
#include <gtsam/linear/NoiseModel.h>
virtual class Unit : gtsam::noiseModel::Isotropic {
static gtsam::noiseModel::Unit* Create(size_t dim);
void print(string s) const;
};
}///\namespace noiseModel
#include <gtsam/linear/Sampler.h>
class Sampler {
Sampler(gtsam::noiseModel::Diagonal* model, int seed);
Sampler(Vector sigmas, int seed);
@ -948,6 +947,7 @@ class GaussianISAM {
gtsam::GaussianBayesNet* jointBayesNet(size_t key1, size_t key2) const;
};
#include <gtsam/linear/GaussianSequentialSolver.h>
class GaussianSequentialSolver {
GaussianSequentialSolver(const gtsam::GaussianFactorGraph& graph,
bool useQR);
@ -957,6 +957,7 @@ class GaussianSequentialSolver {
Matrix marginalCovariance(size_t j) const;
};
#include <gtsam/linear/KalmanFilter.h>
class KalmanFilter {
KalmanFilter(size_t n);
// gtsam::GaussianDensity* init(Vector x0, const gtsam::SharedDiagonal& P0);
@ -979,6 +980,7 @@ class KalmanFilter {
// nonlinear
//*************************************************************************
#include <gtsam/nonlinear/Symbol.h>
class Symbol {
Symbol(char c, size_t j);
Symbol(size_t k);
@ -988,6 +990,7 @@ class Symbol {
char chr() const;
};
#include <gtsam/nonlinear/Ordering.h>
class Ordering {
// Standard Constructors and Named Constructors
Ordering();
@ -1007,7 +1010,6 @@ class Ordering {
gtsam::InvertedOrdering invert() const;
};
#include <gtsam/nonlinear/Ordering.h>
class InvertedOrdering {
InvertedOrdering();
@ -1203,7 +1205,7 @@ virtual class BearingFactor : gtsam::NonlinearFactor {
typedef gtsam::BearingFactor<gtsam::Pose2, gtsam::Point2, gtsam::Rot2> BearingFactor2D;
#include <ProjectionFactor.h>
#include <gtsam/slam/ProjectionFactor.h>
template<POSE, LANDMARK, CALIBRATION>
virtual class GenericProjectionFactor : gtsam::NonlinearFactor {
GenericProjectionFactor(const gtsam::Point2& measured, const gtsam::noiseModel::Base* noiseModel,

View File

@ -119,14 +119,13 @@ if (GTSAM_INSTALL_MATLAB_TOOLBOX)
# Set up codegen
include(GtsamMatlabWrap)
# TODO: generate these includes programmatically
# Choose include flags depending on build process
set(MEX_INCLUDE_ROOT ${GTSAM_SOURCE_ROOT_DIR})
set(MEX_LIB_ROOT ${CMAKE_BINARY_DIR})
set(GTSAM_LIB_DIR ${MEX_LIB_ROOT}/gtsam)
# Generate, build and install toolbox
set(mexFlags ${GTSAM_BUILD_MEX_BINARY_FLAGS} -I${Boost_INCLUDE_DIR} -I${MEX_INCLUDE_ROOT} -I${MEX_INCLUDE_ROOT}/gtsam -I${MEX_INCLUDE_ROOT}/gtsam/base -I${MEX_INCLUDE_ROOT}/gtsam/geometry -I${MEX_INCLUDE_ROOT}/gtsam/linear -I${MEX_INCLUDE_ROOT}/gtsam/discrete -I${MEX_INCLUDE_ROOT}/gtsam/inference -I${MEX_INCLUDE_ROOT}/gtsam/nonlinear -I${MEX_INCLUDE_ROOT}/gtsam/slam)
set(mexFlags ${GTSAM_BUILD_MEX_BINARY_FLAGS} -I${Boost_INCLUDE_DIR} -I${MEX_INCLUDE_ROOT})
# Macro to handle details of setting up targets
# FIXME: issue with dependency between wrap_gtsam and wrap_gtsam_build, only shows up on CMake 2.8.3

View File

@ -89,7 +89,7 @@ if (GTSAM_INSTALL_MATLAB_TOOLBOX)
set(GTSAM_UNSTABLE_LIB_DIR ${MEX_LIB_ROOT}/gtsam_unstable)
# Generate, build and install toolbox
set(mexFlags -I${Boost_INCLUDE_DIR} -I${MEX_INCLUDE_ROOT} -I${MEX_INCLUDE_ROOT}/gtsam_unstable -I${MEX_INCLUDE_ROOT}/gtsam_unstable/dynamics -I${MEX_INCLUDE_ROOT}/gtsam_unstable/discrete)
set(mexFlags -I${Boost_INCLUDE_DIR} -I${MEX_INCLUDE_ROOT})
# Macro to handle details of setting up targets
wrap_library(gtsam_unstable "${mexFlags}" "./" gtsam)

View File

@ -139,13 +139,12 @@ virtual class FullIMUFactor : gtsam::NonlinearFactor {
};
#include <DynamicsPriors.h>
#include <gtsam_unstable/dynamics/DynamicsPriors.h>
virtual class DHeightPrior : gtsam::NonlinearFactor {
DHeightPrior(size_t key, double height, const gtsam::noiseModel::Base* model);
};
#include <DynamicsPriors.h>
virtual class DRollPrior : gtsam::NonlinearFactor {
/** allows for explicit roll parameterization - uses canonical coordinate */
DRollPrior(size_t key, double wx, const gtsam::noiseModel::Base* model);
@ -154,13 +153,11 @@ virtual class DRollPrior : gtsam::NonlinearFactor {
};
#include <DynamicsPriors.h>
virtual class VelocityPrior : gtsam::NonlinearFactor {
VelocityPrior(size_t key, Vector vel, const gtsam::noiseModel::Base* model);
};
#include <DynamicsPriors.h>
virtual class DGroundConstraint : gtsam::NonlinearFactor {
// Primary constructor allows for variable height of the "floor"
DGroundConstraint(size_t key, double height, const gtsam::noiseModel::Base* model);
@ -182,7 +179,6 @@ class Values {
gtsam::PoseRTV pose(size_t key) const;
};
#include <gtsam_unstable/dynamics/imuSystem.h>
class Graph {
Graph();
void print(string s) const;

View File

@ -268,12 +268,6 @@ Class expandClassTemplate(const Class& cls, const string& templateArg, const vec
inst.static_methods = expandMethodTemplate(cls.static_methods, templateArg, instName);
inst.namespaces = cls.namespaces;
inst.using_namespaces = cls.using_namespaces;
bool allIncludesEmpty = true;
BOOST_FOREACH(const string& inc, cls.includes) { if(!inc.empty()) { allIncludesEmpty = false; break; } }
if(allIncludesEmpty)
inst.includes.push_back(cls.name + ".h");
else
inst.includes = cls.includes;
inst.constructor = cls.constructor;
inst.constructor.args_list = expandArgumentListsTemplate(cls.constructor.args_list, templateArg, instName);
inst.constructor.name = inst.name;

View File

@ -40,7 +40,7 @@ struct Class {
// Then the instance variables are set directly by the Module constructor
std::string name; ///< Class name
std::vector<std::string> templateArgs; ///< Template arguments
std::vector<std::string> templateArgs; ///< Template arguments
std::string typedefName; ///< The name to typedef *from*, if this class is actually a typedef, i.e. typedef [typedefName] [name]
bool isVirtual; ///< Whether the class is part of a virtual inheritance chain
std::vector<std::string> qualifiedParent; ///< The *single* parent - the last string is the parent class name, preceededing elements are a namespace stack
@ -48,7 +48,6 @@ struct Class {
StaticMethods static_methods; ///< Static methods
std::vector<std::string> namespaces; ///< Stack of namespaces
std::vector<std::string> using_namespaces;///< default namespaces
std::vector<std::string> includes; ///< header include overrides
Constructor constructor; ///< Class constructors
Deconstructor deconstructor; ///< Deconstructor to deallocate C++ object
bool verbose_; ///< verbose flag

View File

@ -252,12 +252,9 @@ Module::Module(const string& interfacePath,
Rule functions_p = constructor_p | method_p | static_method_p;
Rule include_p = str_p("#include") >> ch_p('<') >> (*(anychar_p - '>'))[assign_a(include_path)] >> ch_p('>');
Rule class_p =
(str_p("")[assign_a(cls,cls0)])
>> (*(include_p[push_back_a(cls.includes, include_path)][assign_a(include_path, null_str)])
>> !(templateInstantiations_p | templateList_p)
>> (!(templateInstantiations_p | templateList_p)
>> !(str_p("virtual")[assign_a(cls.isVirtual, true)])
>> str_p("class")
>> className_p[assign_a(cls.name)]
@ -277,12 +274,13 @@ Module::Module(const string& interfacePath,
[clear_a(templateArgument)]
[clear_a(templateInstantiations)];
Rule include_p = str_p("#include") >> ch_p('<') >> (*(anychar_p - '>'))[push_back_a(includes)] >> ch_p('>');
Rule namespace_def_p =
(*(include_p[push_back_a(includes, include_path)][assign_a(include_path, null_str)])
>> str_p("namespace")
(str_p("namespace")
>> namespace_name_p[push_back_a(namespaces)]
>> ch_p('{')
>> *(class_p | templateSingleInstantiation_p | namespace_def_p | comments_p)
>> *(include_p | class_p | templateSingleInstantiation_p | namespace_def_p | comments_p)
>> str_p("}///\\namespace") // end namespace, avoid confusion with classes
>> !namespace_name_p)
[pop_a(namespaces)];
@ -299,7 +297,7 @@ Module::Module(const string& interfacePath,
[push_back_a(forward_declarations, fwDec)]
[assign_a(fwDec, fwDec0)];
Rule module_content_p = comments_p | using_namespace_p | class_p | templateSingleInstantiation_p | forward_declaration_p | namespace_def_p ;
Rule module_content_p = comments_p | using_namespace_p | include_p | class_p | templateSingleInstantiation_p | forward_declaration_p | namespace_def_p ;
Rule module_p = *module_content_p >> !end_p;
@ -375,24 +373,7 @@ void verifyReturnTypes(const vector<string>& validtypes, const map<string,T>& vt
void Module::generateIncludes(FileWriter& file) const {
// collect includes
vector<string> all_includes;
BOOST_FOREACH(const Class& cls, classes) {
bool added_include = false;
BOOST_FOREACH(const string& s, cls.includes) {
if (!s.empty()) {
all_includes.push_back(s);
added_include = true;
}
}
if (!added_include) // add default include
all_includes.push_back(cls.name + ".h");
}
// Add namespace includes
BOOST_FOREACH(const string& s, includes) {
if(!s.empty())
all_includes.push_back(s);
}
vector<string> all_includes(includes);
// sort and remove duplicates
sort(all_includes.begin(), all_includes.end());

View File

@ -39,7 +39,7 @@ struct Module {
bool verbose; ///< verbose flag
// std::vector<std::string> using_namespaces; ///< all default namespaces
std::vector<ForwardDeclaration> forward_declarations;
std::vector<std::string> includes; ///< header include overrides
std::vector<std::string> includes; ///< Include statements
/// constructor that parses interface file
Module(const std::string& interfacePath,

View File

@ -3,8 +3,6 @@
#include <map>
#include <boost/foreach.hpp>
#include <Point2.h>
#include <Point3.h>
#include <folder/path/to/Test.h>

View File

@ -3,10 +3,6 @@
#include <map>
#include <boost/foreach.hpp>
#include <ClassA.h>
#include <ClassB.h>
#include <ClassC.h>
#include <ClassD.h>
#include <path/to/ns1.h>
#include <path/to/ns1/ClassB.h>
#include <path/to/ns2.h>

View File

@ -35,7 +35,9 @@ class Point3 {
* 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! */

View File

@ -71,7 +71,7 @@ TEST_UNSAFE( wrap, check_exception ) {
}
/* ************************************************************************* */
TEST( wrap, parse ) {
TEST( wrap, parse_geometry ) {
string markup_header_path = topdir + "/wrap/tests";
Module module(markup_header_path.c_str(), "geometry",enable_verbose);
EXPECT_LONGS_EQUAL(3, module.classes.size());
@ -84,6 +84,10 @@ TEST( wrap, parse ) {
EXPECT(assert_equal("VectorNotEigen", module.forward_declarations[0].name));
EXPECT(assert_equal("ns::OtherClass", module.forward_declarations[1].name));
// includes
strvec exp_includes; exp_includes += "folder/path/to/Test.h";
EXPECT(assert_equal(exp_includes, module.includes));
// check first class, Point2
{
Class cls = module.classes.at(0);
@ -136,8 +140,6 @@ TEST( wrap, parse ) {
EXPECT_LONGS_EQUAL( 0, testCls.static_methods.size());
EXPECT_LONGS_EQUAL( 0, testCls.namespaces.size());
EXPECT(assert_equal(exp_using2, testCls.using_namespaces));
strvec exp_includes; exp_includes += "folder/path/to/Test.h";
EXPECT(assert_equal(exp_includes, testCls.includes));
// function to parse: pair<Vector,Matrix> return_pair (Vector v, Matrix A) const;
CHECK(testCls.methods.find("return_pair") != testCls.methods.end());
@ -158,8 +160,11 @@ TEST( wrap, parse_namespaces ) {
{
strvec module_exp_includes;
module_exp_includes += "path/to/ns1.h";
module_exp_includes += "path/to/ns1/ClassB.h";
module_exp_includes += "path/to/ns2.h";
module_exp_includes += "path/to/ns2/ClassA.h";
module_exp_includes += "path/to/ns3.h";
EXPECT(assert_equal(module_exp_includes, module.includes));
}
{
@ -167,8 +172,6 @@ TEST( wrap, parse_namespaces ) {
EXPECT(assert_equal("ClassA", cls.name));
strvec exp_namespaces; exp_namespaces += "ns1";
EXPECT(assert_equal(exp_namespaces, cls.namespaces));
strvec exp_includes; exp_includes;
EXPECT(assert_equal(exp_includes, cls.includes));
}
{
@ -176,8 +179,6 @@ TEST( wrap, parse_namespaces ) {
EXPECT(assert_equal("ClassB", cls.name));
strvec exp_namespaces; exp_namespaces += "ns1";
EXPECT(assert_equal(exp_namespaces, cls.namespaces));
strvec exp_includes; exp_includes += "path/to/ns1/ClassB.h";
EXPECT(assert_equal(exp_includes, cls.includes));
}
{
@ -185,8 +186,6 @@ TEST( wrap, parse_namespaces ) {
EXPECT(assert_equal("ClassA", cls.name));
strvec exp_namespaces; exp_namespaces += "ns2";
EXPECT(assert_equal(exp_namespaces, cls.namespaces));
strvec exp_includes; exp_includes += "path/to/ns2/ClassA.h";
EXPECT(assert_equal(exp_includes, cls.includes));
}
{
@ -194,8 +193,6 @@ TEST( wrap, parse_namespaces ) {
EXPECT(assert_equal("ClassB", cls.name));
strvec exp_namespaces; exp_namespaces += "ns2", "ns3";
EXPECT(assert_equal(exp_namespaces, cls.namespaces));
strvec exp_includes;
EXPECT(assert_equal(exp_includes, cls.includes));
}
{
@ -203,8 +200,6 @@ TEST( wrap, parse_namespaces ) {
EXPECT(assert_equal("ClassC", cls.name));
strvec exp_namespaces; exp_namespaces += "ns2";
EXPECT(assert_equal(exp_namespaces, cls.namespaces));
strvec exp_includes;
EXPECT(assert_equal(exp_includes, cls.includes));
}
{
@ -212,8 +207,6 @@ TEST( wrap, parse_namespaces ) {
EXPECT(assert_equal("ClassD", cls.name));
strvec exp_namespaces;
EXPECT(assert_equal(exp_namespaces, cls.namespaces));
strvec exp_includes;
EXPECT(assert_equal(exp_includes, cls.includes));
}
}
@ -243,7 +236,7 @@ TEST( wrap, matlab_code_namespaces ) {
}
/* ************************************************************************* */
TEST( wrap, matlab_code ) {
TEST( wrap, matlab_code_geometry ) {
// Parse into class object
string header_path = topdir + "/wrap/tests";
Module module(header_path,"geometry",enable_verbose);