More flexible handling of includes in wrap - can now use multiple includes both at the namespace and class levels, and namespace includes do not override the default class-name includes of their enclosed classes.
parent
6eb9d3246f
commit
e9f710a1ac
25
gtsam.h
25
gtsam.h
|
@ -771,11 +771,12 @@ class VariableIndex {
|
|||
// linear
|
||||
//*************************************************************************
|
||||
|
||||
#include <gtsam/linear/NoiseModel.h>
|
||||
namespace noiseModel {
|
||||
#include <gtsam/linear/NoiseModel.h>
|
||||
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);
|
||||
|
@ -783,6 +784,7 @@ 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);
|
||||
|
@ -791,6 +793,7 @@ 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);
|
||||
|
@ -798,6 +801,7 @@ 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;
|
||||
|
@ -1216,9 +1220,9 @@ typedef gtsam::GenericProjectionFactor<gtsam::Pose3, gtsam::Point3, gtsam::Cal3D
|
|||
// Pose2SLAM
|
||||
//*************************************************************************
|
||||
|
||||
#include <gtsam/slam/pose2SLAM.h>
|
||||
namespace pose2SLAM {
|
||||
|
||||
#include <gtsam/slam/pose2SLAM.h>
|
||||
class Values {
|
||||
Values();
|
||||
Values(const pose2SLAM::Values& values);
|
||||
|
@ -1234,6 +1238,7 @@ class Values {
|
|||
Matrix poses() const;
|
||||
};
|
||||
|
||||
#include <gtsam/slam/pose2SLAM.h>
|
||||
class Graph {
|
||||
Graph();
|
||||
Graph(const gtsam::NonlinearFactorGraph& graph);
|
||||
|
@ -1270,9 +1275,9 @@ class Graph {
|
|||
// Pose3SLAM
|
||||
//*************************************************************************
|
||||
|
||||
#include <gtsam/slam/pose3SLAM.h>
|
||||
namespace pose3SLAM {
|
||||
|
||||
#include <gtsam/slam/pose3SLAM.h>
|
||||
class Values {
|
||||
Values();
|
||||
Values(const pose3SLAM::Values& values);
|
||||
|
@ -1288,6 +1293,7 @@ class Values {
|
|||
Matrix translations() const;
|
||||
};
|
||||
|
||||
#include <gtsam/slam/pose3SLAM.h>
|
||||
class Graph {
|
||||
Graph();
|
||||
Graph(const gtsam::NonlinearFactorGraph& graph);
|
||||
|
@ -1324,9 +1330,9 @@ class Graph {
|
|||
// planarSLAM
|
||||
//*************************************************************************
|
||||
|
||||
#include <gtsam/slam/planarSLAM.h>
|
||||
namespace planarSLAM {
|
||||
|
||||
#include <gtsam/slam/planarSLAM.h>
|
||||
class Values {
|
||||
Values();
|
||||
Values(const planarSLAM::Values& values);
|
||||
|
@ -1358,6 +1364,7 @@ class Values {
|
|||
Matrix points() const;
|
||||
};
|
||||
|
||||
#include <gtsam/slam/planarSLAM.h>
|
||||
class Graph {
|
||||
Graph();
|
||||
Graph(const gtsam::NonlinearFactorGraph& graph);
|
||||
|
@ -1396,6 +1403,7 @@ class Graph {
|
|||
void addBearingRange(size_t poseKey, size_t pointKey, const gtsam::Rot2& bearing,double range, const gtsam::noiseModel::Base* noiseModel);
|
||||
};
|
||||
|
||||
#include <gtsam/slam/planarSLAM.h>
|
||||
class Odometry {
|
||||
Odometry(size_t key1, size_t key2, const gtsam::Pose2& measured,
|
||||
const gtsam::noiseModel::Base* model);
|
||||
|
@ -1410,9 +1418,9 @@ class Odometry {
|
|||
// VisualSLAM
|
||||
//*************************************************************************
|
||||
|
||||
#include <gtsam/slam/visualSLAM.h>
|
||||
namespace visualSLAM {
|
||||
|
||||
#include <gtsam/slam/visualSLAM.h>
|
||||
class Values {
|
||||
Values();
|
||||
Values(const visualSLAM::Values& values);
|
||||
|
@ -1446,6 +1454,7 @@ class Values {
|
|||
Matrix points() const;
|
||||
};
|
||||
|
||||
#include <gtsam/slam/visualSLAM.h>
|
||||
class Graph {
|
||||
Graph();
|
||||
Graph(const gtsam::NonlinearFactorGraph& graph);
|
||||
|
@ -1494,6 +1503,7 @@ class Graph {
|
|||
|
||||
};
|
||||
|
||||
#include <gtsam/slam/visualSLAM.h>
|
||||
class ISAM {
|
||||
ISAM();
|
||||
ISAM(int reorderInterval);
|
||||
|
@ -1516,6 +1526,7 @@ class ISAM {
|
|||
gtsam::NonlinearFactorGraph getFactorsUnsafe() const;
|
||||
};
|
||||
|
||||
#include <gtsam/slam/visualSLAM.h>
|
||||
class LevenbergMarquardtOptimizer {
|
||||
double lambda() const;
|
||||
void iterate();
|
||||
|
@ -1532,9 +1543,9 @@ class LevenbergMarquardtOptimizer {
|
|||
// sparse BA
|
||||
//************************************************************************
|
||||
|
||||
#include <gtsam/slam/sparseBA.h>
|
||||
namespace sparseBA {
|
||||
|
||||
#include <gtsam/slam/sparseBA.h>
|
||||
class Values {
|
||||
Values();
|
||||
Values(const sparseBA::Values& values);
|
||||
|
@ -1561,6 +1572,7 @@ class Values {
|
|||
Matrix points() const;
|
||||
};
|
||||
|
||||
#include <gtsam/slam/sparseBA.h>
|
||||
class Graph {
|
||||
Graph();
|
||||
Graph(const gtsam::NonlinearFactorGraph& graph);
|
||||
|
@ -1596,6 +1608,7 @@ class Graph {
|
|||
void addSimpleCameraMeasurement(const gtsam::Point2 &z, gtsam::noiseModel::Base* model, size_t cameraKey, size_t pointKey);
|
||||
};
|
||||
|
||||
#include <gtsam/slam/sparseBA.h>
|
||||
class LevenbergMarquardtOptimizer {
|
||||
double lambda() const;
|
||||
void iterate();
|
||||
|
|
|
@ -171,9 +171,9 @@ virtual class DGroundConstraint : gtsam::NonlinearFactor {
|
|||
|
||||
}///\namespace gtsam
|
||||
|
||||
#include <gtsam_unstable/dynamics/imuSystem.h>
|
||||
namespace imu {
|
||||
|
||||
#include <gtsam_unstable/dynamics/imuSystem.h>
|
||||
class Values {
|
||||
Values();
|
||||
void print(string s) const;
|
||||
|
@ -182,6 +182,7 @@ class Values {
|
|||
gtsam::PoseRTV pose(size_t key) const;
|
||||
};
|
||||
|
||||
#include <gtsam_unstable/dynamics/imuSystem.h>
|
||||
class Graph {
|
||||
Graph();
|
||||
void print(string s) const;
|
||||
|
|
|
@ -84,7 +84,6 @@ Module::Module(const string& interfacePath,
|
|||
Class cls0(enable_verbose),cls(enable_verbose);
|
||||
ForwardDeclaration fwDec0, fwDec;
|
||||
vector<string> namespaces, /// current namespace tag
|
||||
namespace_includes, /// current set of includes
|
||||
namespaces_return, /// namespace for current return type
|
||||
using_namespace_current; /// All namespaces from "using" declarations
|
||||
string templateArgument;
|
||||
|
@ -256,10 +255,11 @@ Module::Module(const string& interfacePath,
|
|||
Rule include_p = str_p("#include") >> ch_p('<') >> (*(anychar_p - '>'))[assign_a(include_path)] >> ch_p('>');
|
||||
|
||||
Rule class_p =
|
||||
(!*include_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)
|
||||
>> !(str_p("virtual")[assign_a(cls.isVirtual, true)])
|
||||
>> str_p("class")[push_back_a(cls.includes, include_path)][assign_a(include_path, null_str)]
|
||||
>> str_p("class")
|
||||
>> className_p[assign_a(cls.name)]
|
||||
>> ((':' >> classParent_p >> '{') | '{')
|
||||
>> *(functions_p | comments_p)
|
||||
|
@ -268,7 +268,6 @@ Module::Module(const string& interfacePath,
|
|||
[assign_a(cls.constructor, constructor)]
|
||||
[assign_a(cls.namespaces, namespaces)]
|
||||
[assign_a(cls.using_namespaces, using_namespace_current)]
|
||||
[append_a(cls.includes, namespace_includes)]
|
||||
[assign_a(deconstructor.name,cls.name)]
|
||||
[assign_a(cls.deconstructor, deconstructor)]
|
||||
[bl::bind(&handle_possible_template, bl::var(classes), bl::var(cls), bl::var(templateArgument), bl::var(templateInstantiations))]
|
||||
|
@ -279,15 +278,14 @@ Module::Module(const string& interfacePath,
|
|||
[clear_a(templateInstantiations)];
|
||||
|
||||
Rule namespace_def_p =
|
||||
(!*include_p
|
||||
>> str_p("namespace")[push_back_a(namespace_includes, include_path)][assign_a(include_path, null_str)]
|
||||
(*(include_p[push_back_a(includes, include_path)][assign_a(include_path, null_str)])
|
||||
>> str_p("namespace")
|
||||
>> namespace_name_p[push_back_a(namespaces)]
|
||||
>> ch_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)]
|
||||
[pop_a(namespace_includes)];
|
||||
[pop_a(namespaces)];
|
||||
|
||||
Rule using_namespace_p =
|
||||
str_p("using") >> str_p("namespace")
|
||||
|
@ -390,6 +388,12 @@ void Module::generateIncludes(FileWriter& file) const {
|
|||
all_includes.push_back(cls.name + ".h");
|
||||
}
|
||||
|
||||
// Add namespace includes
|
||||
BOOST_FOREACH(const string& s, includes) {
|
||||
if(!s.empty())
|
||||
all_includes.push_back(s);
|
||||
}
|
||||
|
||||
// sort and remove duplicates
|
||||
sort(all_includes.begin(), all_includes.end());
|
||||
vector<string>::const_iterator last_include = unique(all_includes.begin(), all_includes.end());
|
||||
|
|
|
@ -39,6 +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
|
||||
|
||||
/// constructor that parses interface file
|
||||
Module(const std::string& interfacePath,
|
||||
|
|
Loading…
Reference in New Issue