Merged from branch 'trunk' into 'branches/remove_slam_namespaces'
commit
415881e0e6
26
gtsam.h
26
gtsam.h
|
|
@ -36,19 +36,19 @@
|
||||||
* Namespace definitions
|
* Namespace definitions
|
||||||
* - Names of namespaces must start with a lowercase letter
|
* - Names of namespaces must start with a lowercase letter
|
||||||
* - start a namespace with "namespace {"
|
* - start a namespace with "namespace {"
|
||||||
* - end a namespace with exactly "}///\namespace [namespace_name]", optionally adding the name of the namespace
|
* - end a namespace with exactly "}"
|
||||||
* - This ending is not C++ standard, and must contain "}///\namespace" to parse
|
|
||||||
* - Namespaces can be nested
|
* - Namespaces can be nested
|
||||||
* Namespace usage
|
* Namespace usage
|
||||||
* - Namespaces can be specified for classes in arguments and return values
|
* - Namespaces can be specified for classes in arguments and return values
|
||||||
* - In each case, the namespace must be fully specified, e.g., "namespace1::namespace2::ClassName"
|
* - In each case, the namespace must be fully specified, e.g., "namespace1::namespace2::ClassName"
|
||||||
* Using namespace: FIXME: this functionality is currently broken
|
|
||||||
* - 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
|
* Includes in C++ wrappers
|
||||||
* - All includes will be collected and added in a single file
|
* - All includes will be collected and added in a single file
|
||||||
* - All namespaces must have angle brackets: <path>
|
* - All namespaces must have angle brackets: <path>
|
||||||
* - No default includes will be added
|
* - No default includes will be added
|
||||||
|
* Global/Namespace functions
|
||||||
|
* - Functions specified outside of a class are global
|
||||||
|
* - Can be overloaded with different arguments
|
||||||
|
* - Can have multiple functions of the same name in different namespaces
|
||||||
* Using classes defined in other modules
|
* 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
|
* - If you are using a class 'OtherClass' not wrapped in this definition file, add "class OtherClass;" to avoid a dependency error
|
||||||
* Virtual inheritance
|
* Virtual inheritance
|
||||||
|
|
@ -75,7 +75,6 @@
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Status:
|
* Status:
|
||||||
* - TODO: global functions
|
|
||||||
* - TODO: default values for arguments
|
* - TODO: default values for arguments
|
||||||
* - TODO: Handle gtsam::Rot3M conversions to quaternions
|
* - TODO: Handle gtsam::Rot3M conversions to quaternions
|
||||||
*/
|
*/
|
||||||
|
|
@ -86,6 +85,9 @@ namespace gtsam {
|
||||||
// base
|
// base
|
||||||
//*************************************************************************
|
//*************************************************************************
|
||||||
|
|
||||||
|
/** gtsam namespace functions */
|
||||||
|
bool linear_independent(Matrix A, Matrix B, double tol);
|
||||||
|
|
||||||
virtual class Value {
|
virtual class Value {
|
||||||
// No constructors because this is an abstract class
|
// No constructors because this is an abstract class
|
||||||
|
|
||||||
|
|
@ -1385,7 +1387,7 @@ virtual class GenericProjectionFactor : gtsam::NonlinearFactor {
|
||||||
typedef gtsam::GenericProjectionFactor<gtsam::Pose3, gtsam::Point3, gtsam::Cal3_S2> GenericProjectionFactorCal3_S2;
|
typedef gtsam::GenericProjectionFactor<gtsam::Pose3, gtsam::Point3, gtsam::Cal3_S2> GenericProjectionFactorCal3_S2;
|
||||||
typedef gtsam::GenericProjectionFactor<gtsam::Pose3, gtsam::Point3, gtsam::Cal3DS2> GenericProjectionFactorCal3DS2;
|
typedef gtsam::GenericProjectionFactor<gtsam::Pose3, gtsam::Point3, gtsam::Cal3DS2> GenericProjectionFactorCal3DS2;
|
||||||
|
|
||||||
}///\namespace gtsam
|
} //\namespace gtsam
|
||||||
|
|
||||||
//*************************************************************************
|
//*************************************************************************
|
||||||
// Pose2SLAM
|
// Pose2SLAM
|
||||||
|
|
@ -1440,7 +1442,7 @@ class Graph {
|
||||||
gtsam::Marginals marginals(const pose2SLAM::Values& solution) const;
|
gtsam::Marginals marginals(const pose2SLAM::Values& solution) const;
|
||||||
};
|
};
|
||||||
|
|
||||||
}///\namespace pose2SLAM
|
} //\namespace pose2SLAM
|
||||||
|
|
||||||
//*************************************************************************
|
//*************************************************************************
|
||||||
// Pose3SLAM
|
// Pose3SLAM
|
||||||
|
|
@ -1495,7 +1497,7 @@ class Graph {
|
||||||
gtsam::Marginals marginals(const pose3SLAM::Values& solution) const;
|
gtsam::Marginals marginals(const pose3SLAM::Values& solution) const;
|
||||||
};
|
};
|
||||||
|
|
||||||
}///\namespace pose3SLAM
|
} //\namespace pose3SLAM
|
||||||
|
|
||||||
//*************************************************************************
|
//*************************************************************************
|
||||||
// planarSLAM
|
// planarSLAM
|
||||||
|
|
@ -1583,7 +1585,7 @@ class Odometry {
|
||||||
const gtsam::Ordering& ordering) const;
|
const gtsam::Ordering& ordering) const;
|
||||||
};
|
};
|
||||||
|
|
||||||
}///\namespace planarSLAM
|
} //\namespace planarSLAM
|
||||||
|
|
||||||
//*************************************************************************
|
//*************************************************************************
|
||||||
// VisualSLAM
|
// VisualSLAM
|
||||||
|
|
@ -1708,7 +1710,7 @@ class LevenbergMarquardtOptimizer {
|
||||||
visualSLAM::Values values() const;
|
visualSLAM::Values values() const;
|
||||||
};
|
};
|
||||||
|
|
||||||
}///\namespace visualSLAM
|
} //\namespace visualSLAM
|
||||||
|
|
||||||
//************************************************************************
|
//************************************************************************
|
||||||
// sparse BA
|
// sparse BA
|
||||||
|
|
@ -1789,5 +1791,5 @@ class LevenbergMarquardtOptimizer {
|
||||||
sparseBA::Values optimizeSafely();
|
sparseBA::Values optimizeSafely();
|
||||||
sparseBA::Values values() const;
|
sparseBA::Values values() const;
|
||||||
};
|
};
|
||||||
}///\namespace sparseBA
|
} //\namespace sparseBA
|
||||||
|
|
||||||
|
|
|
||||||
|
|
@ -90,7 +90,7 @@ public:
|
||||||
|
|
||||||
/** Conversion to a standard STL container */
|
/** Conversion to a standard STL container */
|
||||||
operator std::vector<VALUE>() const {
|
operator std::vector<VALUE>() const {
|
||||||
return std::vector<VALUE>(begin(), end());
|
return std::vector<VALUE>(this->begin(), this->end());
|
||||||
}
|
}
|
||||||
|
|
||||||
private:
|
private:
|
||||||
|
|
|
||||||
|
|
@ -1,63 +0,0 @@
|
||||||
/**
|
|
||||||
* @file ilm3DSystem.cpp
|
|
||||||
* @brief Implementations of ilm 3D domain
|
|
||||||
* @author Alex Cunningham
|
|
||||||
*/
|
|
||||||
|
|
||||||
#include <gtsam_unstable/dynamics/imuSystem.h>
|
|
||||||
#include <gtsam/nonlinear/LevenbergMarquardtOptimizer.h>
|
|
||||||
|
|
||||||
namespace imu {
|
|
||||||
|
|
||||||
using namespace gtsam;
|
|
||||||
|
|
||||||
/* ************************************************************************* */
|
|
||||||
void Graph::addPrior(Key key, const PoseRTV& pose, const SharedNoiseModel& noiseModel) {
|
|
||||||
add(Prior(key, pose, noiseModel));
|
|
||||||
}
|
|
||||||
|
|
||||||
/* ************************************************************************* */
|
|
||||||
void Graph::addConstraint(Key key, const PoseRTV& pose) {
|
|
||||||
add(Constraint(key, pose));
|
|
||||||
}
|
|
||||||
|
|
||||||
/* ************************************************************************* */
|
|
||||||
void Graph::addHeightPrior(Key key, double z, const SharedNoiseModel& noiseModel) {
|
|
||||||
add(DHeightPrior(key, z, noiseModel));
|
|
||||||
}
|
|
||||||
|
|
||||||
/* ************************************************************************* */
|
|
||||||
void Graph::addFullIMUMeasurement(Key key1, Key key2,
|
|
||||||
const Vector& accel, const Vector& gyro, double dt, const SharedNoiseModel& noiseModel) {
|
|
||||||
add(FullIMUMeasurement(accel, gyro, dt, key1, key2, noiseModel));
|
|
||||||
}
|
|
||||||
|
|
||||||
/* ************************************************************************* */
|
|
||||||
void Graph::addIMUMeasurement(Key key1, Key key2,
|
|
||||||
const Vector& accel, const Vector& gyro, double dt, const SharedNoiseModel& noiseModel) {
|
|
||||||
add(IMUMeasurement(accel, gyro, dt, key1, key2, noiseModel));
|
|
||||||
}
|
|
||||||
|
|
||||||
/* ************************************************************************* */
|
|
||||||
void Graph::addVelocityConstraint(Key key1, Key key2, double dt, const SharedNoiseModel& noiseModel) {
|
|
||||||
add(VelocityConstraint(key1, key2, dt, noiseModel));
|
|
||||||
}
|
|
||||||
|
|
||||||
/* ************************************************************************* */
|
|
||||||
void Graph::addBetween(Key key1, Key key2, const PoseRTV& z, const SharedNoiseModel& noiseModel) {
|
|
||||||
add(Between(key1, key2, z, noiseModel));
|
|
||||||
}
|
|
||||||
|
|
||||||
/* ************************************************************************* */
|
|
||||||
void Graph::addRange(Key key1, Key key2, double z, const SharedNoiseModel& noiseModel) {
|
|
||||||
add(Range(key1, key2, z, noiseModel));
|
|
||||||
}
|
|
||||||
|
|
||||||
/* ************************************************************************* */
|
|
||||||
Values Graph::optimize(const Values& init) const {
|
|
||||||
return LevenbergMarquardtOptimizer(*this, init).optimize();
|
|
||||||
}
|
|
||||||
/* ************************************************************************* */
|
|
||||||
|
|
||||||
} // \namespace imu
|
|
||||||
|
|
||||||
|
|
@ -1,78 +0,0 @@
|
||||||
/**
|
|
||||||
* @file imuSystem.h
|
|
||||||
* @brief A 3D Dynamic system domain as a demonstration of IMU factors
|
|
||||||
* @author Alex Cunningham
|
|
||||||
*/
|
|
||||||
|
|
||||||
#pragma once
|
|
||||||
|
|
||||||
#include <gtsam/slam/BetweenFactor.h>
|
|
||||||
#include <gtsam/slam/PriorFactor.h>
|
|
||||||
#include <gtsam/slam/RangeFactor.h>
|
|
||||||
#include <gtsam/slam/PartialPriorFactor.h>
|
|
||||||
#include <gtsam/nonlinear/NonlinearEquality.h>
|
|
||||||
#include <gtsam/nonlinear/NonlinearFactorGraph.h>
|
|
||||||
|
|
||||||
#include <gtsam_unstable/dynamics/PoseRTV.h>
|
|
||||||
#include <gtsam_unstable/dynamics/IMUFactor.h>
|
|
||||||
#include <gtsam_unstable/dynamics/FullIMUFactor.h>
|
|
||||||
#include <gtsam_unstable/dynamics/VelocityConstraint.h>
|
|
||||||
#include <gtsam_unstable/dynamics/DynamicsPriors.h>
|
|
||||||
|
|
||||||
/**
|
|
||||||
* This domain focuses on a single class of variables: PoseRTV, which
|
|
||||||
* models a dynamic pose operating with IMU measurements and assorted priors.
|
|
||||||
*
|
|
||||||
* There are also partial priors that constraint certain components of the
|
|
||||||
* poses, as well as between and range factors to model other between-pose
|
|
||||||
* information.
|
|
||||||
*/
|
|
||||||
namespace imu {
|
|
||||||
|
|
||||||
struct Values : public gtsam::Values {
|
|
||||||
typedef gtsam::Values Base;
|
|
||||||
|
|
||||||
Values() {}
|
|
||||||
Values(const Values& values) : Base(values) {}
|
|
||||||
Values(const Base& values) : Base(values) {}
|
|
||||||
|
|
||||||
void insertPose(gtsam::Key key, const gtsam::PoseRTV& pose) { insert(key, pose); }
|
|
||||||
gtsam::PoseRTV pose(gtsam::Key key) const { return at<gtsam::PoseRTV>(key); }
|
|
||||||
};
|
|
||||||
|
|
||||||
// factors
|
|
||||||
typedef gtsam::IMUFactor<gtsam::PoseRTV> IMUMeasurement; // IMU between measurements
|
|
||||||
typedef gtsam::FullIMUFactor<gtsam::PoseRTV> FullIMUMeasurement; // Full-state IMU between measurements
|
|
||||||
typedef gtsam::BetweenFactor<gtsam::PoseRTV> Between; // full odometry (including velocity)
|
|
||||||
typedef gtsam::NonlinearEquality<gtsam::PoseRTV> Constraint;
|
|
||||||
typedef gtsam::PriorFactor<gtsam::PoseRTV> Prior;
|
|
||||||
typedef gtsam::RangeFactor<gtsam::PoseRTV, gtsam::PoseRTV> Range;
|
|
||||||
|
|
||||||
// graph components
|
|
||||||
struct Graph : public gtsam::NonlinearFactorGraph {
|
|
||||||
typedef gtsam::NonlinearFactorGraph Base;
|
|
||||||
|
|
||||||
Graph() {}
|
|
||||||
Graph(const Base& graph) : Base(graph) {}
|
|
||||||
Graph(const Graph& graph) : Base(graph) {}
|
|
||||||
|
|
||||||
// prior factors
|
|
||||||
void addPrior(size_t key, const gtsam::PoseRTV& pose, const gtsam::SharedNoiseModel& noiseModel);
|
|
||||||
void addConstraint(size_t key, const gtsam::PoseRTV& pose);
|
|
||||||
void addHeightPrior(size_t key, double z, const gtsam::SharedNoiseModel& noiseModel);
|
|
||||||
|
|
||||||
// inertial factors
|
|
||||||
void addFullIMUMeasurement(size_t key1, size_t key2, const gtsam::Vector& accel, const gtsam::Vector& gyro, double dt, const gtsam::SharedNoiseModel& noiseModel);
|
|
||||||
void addIMUMeasurement(size_t key1, size_t key2, const gtsam::Vector& accel, const gtsam::Vector& gyro, double dt, const gtsam::SharedNoiseModel& noiseModel);
|
|
||||||
void addVelocityConstraint(size_t key1, size_t key2, double dt, const gtsam::SharedNoiseModel& noiseModel);
|
|
||||||
|
|
||||||
// other measurements
|
|
||||||
void addBetween(size_t key1, size_t key2, const gtsam::PoseRTV& z, const gtsam::SharedNoiseModel& noiseModel);
|
|
||||||
void addRange(size_t key1, size_t key2, double z, const gtsam::SharedNoiseModel& noiseModel);
|
|
||||||
|
|
||||||
// optimization
|
|
||||||
Values optimize(const Values& init) const;
|
|
||||||
};
|
|
||||||
|
|
||||||
} // \namespace imu
|
|
||||||
|
|
||||||
|
|
@ -7,23 +7,37 @@
|
||||||
|
|
||||||
#include <CppUnitLite/TestHarness.h>
|
#include <CppUnitLite/TestHarness.h>
|
||||||
|
|
||||||
#include <gtsam_unstable/dynamics/imuSystem.h>
|
#include <gtsam/slam/BetweenFactor.h>
|
||||||
|
#include <gtsam/slam/PriorFactor.h>
|
||||||
|
#include <gtsam/slam/RangeFactor.h>
|
||||||
|
#include <gtsam/slam/PartialPriorFactor.h>
|
||||||
|
#include <gtsam/nonlinear/NonlinearEquality.h>
|
||||||
|
#include <gtsam/nonlinear/EasyFactorGraph.h>
|
||||||
|
|
||||||
|
#include <gtsam_unstable/dynamics/IMUFactor.h>
|
||||||
|
#include <gtsam_unstable/dynamics/FullIMUFactor.h>
|
||||||
|
#include <gtsam_unstable/dynamics/VelocityConstraint.h>
|
||||||
|
#include <gtsam_unstable/dynamics/DynamicsPriors.h>
|
||||||
|
|
||||||
using namespace std;
|
using namespace std;
|
||||||
using namespace gtsam;
|
using namespace gtsam;
|
||||||
using namespace imu;
|
|
||||||
|
|
||||||
const double tol=1e-5;
|
const double tol=1e-5;
|
||||||
|
|
||||||
static const Key x0 = 0, x1 = 1, x2 = 2, x3 = 3, x4 = 4;
|
static const Key x0 = 0, x1 = 1, x2 = 2, x3 = 3, x4 = 4;
|
||||||
static const Vector g = delta(3, 2, -9.81);
|
static const Vector g = delta(3, 2, -9.81);
|
||||||
|
|
||||||
|
//typedef gtsam::IMUFactor<gtsam::PoseRTV> IMUFactor<PoseRTV>; // IMU between measurements
|
||||||
|
//typedef gtsam::FullIMUFactor<gtsam::PoseRTV> IMUFactor<PoseRTV>; // Full-state IMU between measurements
|
||||||
|
//typedef gtsam::BetweenFactor<gtsam::PoseRTV> Between; // full odometry (including velocity)
|
||||||
|
//typedef gtsam::NonlinearEquality<gtsam::PoseRTV> Constraint;
|
||||||
|
//typedef gtsam::PriorFactor<gtsam::PoseRTV> Prior;
|
||||||
|
//typedef gtsam::RangeFactor<gtsam::PoseRTV, gtsam::PoseRTV> Range;
|
||||||
|
|
||||||
/* ************************************************************************* */
|
/* ************************************************************************* */
|
||||||
TEST(testIMUSystem, instantiations) {
|
TEST(testIMUSystem, instantiations) {
|
||||||
// just checking for compilation
|
// just checking for compilation
|
||||||
PoseRTV x1_v;
|
PoseRTV x1_v;
|
||||||
imu::Values local_values;
|
|
||||||
Graph graph;
|
|
||||||
|
|
||||||
gtsam::SharedNoiseModel model1 = gtsam::noiseModel::Unit::Create(1);
|
gtsam::SharedNoiseModel model1 = gtsam::noiseModel::Unit::Create(1);
|
||||||
gtsam::SharedNoiseModel model3 = gtsam::noiseModel::Unit::Create(3);
|
gtsam::SharedNoiseModel model3 = gtsam::noiseModel::Unit::Create(3);
|
||||||
|
|
@ -32,13 +46,13 @@ TEST(testIMUSystem, instantiations) {
|
||||||
|
|
||||||
Vector accel = ones(3), gyro = ones(3);
|
Vector accel = ones(3), gyro = ones(3);
|
||||||
|
|
||||||
IMUMeasurement imu(accel, gyro, 0.01, x1, x2, model6);
|
IMUFactor<PoseRTV> imu(accel, gyro, 0.01, x1, x2, model6);
|
||||||
FullIMUMeasurement full_imu(accel, gyro, 0.01, x1, x2, model9);
|
FullIMUFactor<PoseRTV> full_imu(accel, gyro, 0.01, x1, x2, model9);
|
||||||
Constraint poseHardPrior(x1, x1_v);
|
NonlinearEquality<gtsam::PoseRTV> poseHardPrior(x1, x1_v);
|
||||||
Between odom(x1, x2, x1_v, model9);
|
BetweenFactor<gtsam::PoseRTV> odom(x1, x2, x1_v, model9);
|
||||||
Range range(x1, x2, 1.0, model1);
|
RangeFactor<gtsam::PoseRTV, gtsam::PoseRTV> range(x1, x2, 1.0, model1);
|
||||||
VelocityConstraint constraint(x1, x2, 0.1, 10000);
|
VelocityConstraint constraint(x1, x2, 0.1, 10000);
|
||||||
Prior posePrior(x1, x1_v, model9);
|
PriorFactor<gtsam::PoseRTV> posePrior(x1, x1_v, model9);
|
||||||
DHeightPrior heightPrior(x1, 0.1, model1);
|
DHeightPrior heightPrior(x1, 0.1, model1);
|
||||||
VelocityPrior velPrior(x1, ones(3), model3);
|
VelocityPrior velPrior(x1, ones(3), model3);
|
||||||
}
|
}
|
||||||
|
|
@ -60,17 +74,17 @@ TEST( testIMUSystem, optimize_chain ) {
|
||||||
imu34 = pose3.imuPrediction(pose4, dt);
|
imu34 = pose3.imuPrediction(pose4, dt);
|
||||||
|
|
||||||
// assemble simple graph with IMU measurements and velocity constraints
|
// assemble simple graph with IMU measurements and velocity constraints
|
||||||
Graph graph;
|
EasyFactorGraph graph;
|
||||||
graph.add(Constraint(x1, pose1));
|
graph.add(NonlinearEquality<gtsam::PoseRTV>(x1, pose1));
|
||||||
graph.add(IMUMeasurement(imu12, dt, x1, x2, model));
|
graph.add(IMUFactor<PoseRTV>(imu12, dt, x1, x2, model));
|
||||||
graph.add(IMUMeasurement(imu23, dt, x2, x3, model));
|
graph.add(IMUFactor<PoseRTV>(imu23, dt, x2, x3, model));
|
||||||
graph.add(IMUMeasurement(imu34, dt, x3, x4, model));
|
graph.add(IMUFactor<PoseRTV>(imu34, dt, x3, x4, model));
|
||||||
graph.add(VelocityConstraint(x1, x2, dt));
|
graph.add(VelocityConstraint(x1, x2, dt));
|
||||||
graph.add(VelocityConstraint(x2, x3, dt));
|
graph.add(VelocityConstraint(x2, x3, dt));
|
||||||
graph.add(VelocityConstraint(x3, x4, dt));
|
graph.add(VelocityConstraint(x3, x4, dt));
|
||||||
|
|
||||||
// ground truth values
|
// ground truth values
|
||||||
imu::Values true_values;
|
Values true_values;
|
||||||
true_values.insert(x1, pose1);
|
true_values.insert(x1, pose1);
|
||||||
true_values.insert(x2, pose2);
|
true_values.insert(x2, pose2);
|
||||||
true_values.insert(x3, pose3);
|
true_values.insert(x3, pose3);
|
||||||
|
|
@ -80,13 +94,13 @@ TEST( testIMUSystem, optimize_chain ) {
|
||||||
EXPECT_DOUBLES_EQUAL(0, graph.error(true_values), 1e-5);
|
EXPECT_DOUBLES_EQUAL(0, graph.error(true_values), 1e-5);
|
||||||
|
|
||||||
// initialize with zero values and optimize
|
// initialize with zero values and optimize
|
||||||
imu::Values values;
|
Values values;
|
||||||
values.insert(x1, PoseRTV());
|
values.insert(x1, PoseRTV());
|
||||||
values.insert(x2, PoseRTV());
|
values.insert(x2, PoseRTV());
|
||||||
values.insert(x3, PoseRTV());
|
values.insert(x3, PoseRTV());
|
||||||
values.insert(x4, PoseRTV());
|
values.insert(x4, PoseRTV());
|
||||||
|
|
||||||
imu::Values actual = graph.optimize(values);
|
Values actual = graph.optimize(values);
|
||||||
EXPECT(assert_equal(true_values, actual, tol));
|
EXPECT(assert_equal(true_values, actual, tol));
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
@ -107,14 +121,14 @@ TEST( testIMUSystem, optimize_chain_fullfactor ) {
|
||||||
imu34 = pose3.imuPrediction(pose4, dt);
|
imu34 = pose3.imuPrediction(pose4, dt);
|
||||||
|
|
||||||
// assemble simple graph with IMU measurements and velocity constraints
|
// assemble simple graph with IMU measurements and velocity constraints
|
||||||
Graph graph;
|
EasyFactorGraph graph;
|
||||||
graph.add(Constraint(x1, pose1));
|
graph.add(NonlinearEquality<gtsam::PoseRTV>(x1, pose1));
|
||||||
graph.add(FullIMUMeasurement(imu12, dt, x1, x2, model));
|
graph.add(FullIMUFactor<PoseRTV>(imu12, dt, x1, x2, model));
|
||||||
graph.add(FullIMUMeasurement(imu23, dt, x2, x3, model));
|
graph.add(FullIMUFactor<PoseRTV>(imu23, dt, x2, x3, model));
|
||||||
graph.add(FullIMUMeasurement(imu34, dt, x3, x4, model));
|
graph.add(FullIMUFactor<PoseRTV>(imu34, dt, x3, x4, model));
|
||||||
|
|
||||||
// ground truth values
|
// ground truth values
|
||||||
imu::Values true_values;
|
Values true_values;
|
||||||
true_values.insert(x1, pose1);
|
true_values.insert(x1, pose1);
|
||||||
true_values.insert(x2, pose2);
|
true_values.insert(x2, pose2);
|
||||||
true_values.insert(x3, pose3);
|
true_values.insert(x3, pose3);
|
||||||
|
|
@ -124,7 +138,7 @@ TEST( testIMUSystem, optimize_chain_fullfactor ) {
|
||||||
EXPECT_DOUBLES_EQUAL(0, graph.error(true_values), 1e-5);
|
EXPECT_DOUBLES_EQUAL(0, graph.error(true_values), 1e-5);
|
||||||
|
|
||||||
// initialize with zero values and optimize
|
// initialize with zero values and optimize
|
||||||
imu::Values values;
|
Values values;
|
||||||
values.insert(x1, PoseRTV());
|
values.insert(x1, PoseRTV());
|
||||||
values.insert(x2, PoseRTV());
|
values.insert(x2, PoseRTV());
|
||||||
values.insert(x3, PoseRTV());
|
values.insert(x3, PoseRTV());
|
||||||
|
|
@ -132,7 +146,7 @@ TEST( testIMUSystem, optimize_chain_fullfactor ) {
|
||||||
|
|
||||||
cout << "Initial Error: " << graph.error(values) << endl; // Initial error is 0.5 - need better prediction model
|
cout << "Initial Error: " << graph.error(values) << endl; // Initial error is 0.5 - need better prediction model
|
||||||
|
|
||||||
imu::Values actual = graph.optimize(values);
|
Values actual = graph.optimize(values);
|
||||||
// EXPECT(assert_equal(true_values, actual, tol)); // FAIL
|
// EXPECT(assert_equal(true_values, actual, tol)); // FAIL
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
@ -147,10 +161,10 @@ TEST( testIMUSystem, linear_trajectory) {
|
||||||
Vector gyro = delta(3, 0, 0.1); // constant rotation
|
Vector gyro = delta(3, 0, 0.1); // constant rotation
|
||||||
SharedDiagonal model = noiseModel::Unit::Create(9);
|
SharedDiagonal model = noiseModel::Unit::Create(9);
|
||||||
|
|
||||||
imu::Values true_traj, init_traj;
|
Values true_traj, init_traj;
|
||||||
Graph graph;
|
EasyFactorGraph graph;
|
||||||
|
|
||||||
graph.add(Constraint(x0, start));
|
graph.add(NonlinearEquality<gtsam::PoseRTV>(x0, start));
|
||||||
true_traj.insert(x0, start);
|
true_traj.insert(x0, start);
|
||||||
init_traj.insert(x0, start);
|
init_traj.insert(x0, start);
|
||||||
|
|
||||||
|
|
@ -159,7 +173,7 @@ TEST( testIMUSystem, linear_trajectory) {
|
||||||
for (size_t i=1; i<nrPoses; ++i) {
|
for (size_t i=1; i<nrPoses; ++i) {
|
||||||
Key xA = i-1, xB = i;
|
Key xA = i-1, xB = i;
|
||||||
cur_pose = cur_pose.generalDynamics(accel, gyro, dt);
|
cur_pose = cur_pose.generalDynamics(accel, gyro, dt);
|
||||||
graph.add(FullIMUMeasurement(accel - g, gyro, dt, xA, xB, model));
|
graph.add(FullIMUFactor<PoseRTV>(accel - g, gyro, dt, xA, xB, model));
|
||||||
true_traj.insert(xB, cur_pose);
|
true_traj.insert(xB, cur_pose);
|
||||||
init_traj.insert(xB, PoseRTV());
|
init_traj.insert(xB, PoseRTV());
|
||||||
}
|
}
|
||||||
|
|
|
||||||
|
|
@ -4,10 +4,10 @@
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#include <CppUnitLite/TestHarness.h>
|
#include <CppUnitLite/TestHarness.h>
|
||||||
#include <gtsam_unstable/dynamics/imuSystem.h>
|
|
||||||
|
#include <gtsam_unstable/dynamics/VelocityConstraint.h>
|
||||||
|
|
||||||
using namespace gtsam;
|
using namespace gtsam;
|
||||||
using namespace imu;
|
|
||||||
|
|
||||||
const double tol=1e-5;
|
const double tol=1e-5;
|
||||||
|
|
||||||
|
|
|
||||||
|
|
@ -102,7 +102,7 @@ virtual class NonlinearEquality : gtsam::NonlinearFactor {
|
||||||
NonlinearEquality(size_t j, const T& feasible, double error_gain);
|
NonlinearEquality(size_t j, const T& feasible, double error_gain);
|
||||||
};
|
};
|
||||||
|
|
||||||
|
#include <gtsam_unstable/dynamics/IMUFactor.h>
|
||||||
template<POSE = {gtsam::PoseRTV}>
|
template<POSE = {gtsam::PoseRTV}>
|
||||||
virtual class IMUFactor : gtsam::NonlinearFactor {
|
virtual class IMUFactor : gtsam::NonlinearFactor {
|
||||||
/** Standard constructor */
|
/** Standard constructor */
|
||||||
|
|
@ -120,7 +120,7 @@ virtual class IMUFactor : gtsam::NonlinearFactor {
|
||||||
size_t key2() const;
|
size_t key2() const;
|
||||||
};
|
};
|
||||||
|
|
||||||
|
#include <gtsam_unstable/dynamics/FullIMUFactor.h>
|
||||||
template<POSE = {gtsam::PoseRTV}>
|
template<POSE = {gtsam::PoseRTV}>
|
||||||
virtual class FullIMUFactor : gtsam::NonlinearFactor {
|
virtual class FullIMUFactor : gtsam::NonlinearFactor {
|
||||||
/** Standard constructor */
|
/** Standard constructor */
|
||||||
|
|
@ -167,38 +167,3 @@ virtual class DGroundConstraint : gtsam::NonlinearFactor {
|
||||||
|
|
||||||
|
|
||||||
}///\namespace gtsam
|
}///\namespace gtsam
|
||||||
|
|
||||||
namespace imu {
|
|
||||||
|
|
||||||
#include <gtsam_unstable/dynamics/imuSystem.h>
|
|
||||||
class Values {
|
|
||||||
Values();
|
|
||||||
void print(string s) const;
|
|
||||||
|
|
||||||
void insertPose(size_t key, const gtsam::PoseRTV& pose);
|
|
||||||
gtsam::PoseRTV pose(size_t key) const;
|
|
||||||
};
|
|
||||||
|
|
||||||
class Graph {
|
|
||||||
Graph();
|
|
||||||
void print(string s) const;
|
|
||||||
|
|
||||||
// prior factors
|
|
||||||
void addPrior(size_t key, const gtsam::PoseRTV& pose, const gtsam::noiseModel::Base* noiseModel);
|
|
||||||
void addConstraint(size_t key, const gtsam::PoseRTV& pose);
|
|
||||||
void addHeightPrior(size_t key, double z, const gtsam::noiseModel::Base* noiseModel);
|
|
||||||
|
|
||||||
// inertial factors
|
|
||||||
void addFullIMUMeasurement(size_t key1, size_t key2, const Vector& accel, const Vector& gyro, double dt, const gtsam::noiseModel::Base* noiseModel);
|
|
||||||
void addIMUMeasurement(size_t key1, size_t key2, const Vector& accel, const Vector& gyro, double dt, const gtsam::noiseModel::Base* noiseModel);
|
|
||||||
void addVelocityConstraint(size_t key1, size_t key2, double dt, const gtsam::noiseModel::Base* noiseModel);
|
|
||||||
|
|
||||||
// other measurements
|
|
||||||
void addBetween(size_t key1, size_t key2, const gtsam::PoseRTV& z, const gtsam::noiseModel::Base* noiseModel);
|
|
||||||
void addRange(size_t key1, size_t key2, double z, const gtsam::noiseModel::Base* noiseModel);
|
|
||||||
|
|
||||||
// optimization
|
|
||||||
imu::Values optimize(const imu::Values& init) const;
|
|
||||||
};
|
|
||||||
|
|
||||||
}///\namespace imu
|
|
||||||
|
|
|
||||||
|
|
@ -24,7 +24,6 @@
|
||||||
#include <stdint.h> // works on Linux GCC
|
#include <stdint.h> // works on Linux GCC
|
||||||
|
|
||||||
#include <boost/foreach.hpp>
|
#include <boost/foreach.hpp>
|
||||||
#include <boost/filesystem.hpp>
|
|
||||||
#include <boost/lexical_cast.hpp>
|
#include <boost/lexical_cast.hpp>
|
||||||
|
|
||||||
#include "Class.h"
|
#include "Class.h"
|
||||||
|
|
@ -40,18 +39,7 @@ void Class::matlab_proxy(const string& toolboxPath, const string& wrapperName,
|
||||||
FileWriter& wrapperFile, vector<string>& functionNames) const {
|
FileWriter& wrapperFile, vector<string>& functionNames) const {
|
||||||
|
|
||||||
// Create namespace folders
|
// Create namespace folders
|
||||||
{
|
createNamespaceStructure(namespaces, toolboxPath);
|
||||||
using namespace boost::filesystem;
|
|
||||||
path curPath = toolboxPath;
|
|
||||||
BOOST_FOREACH(const string& subdir, namespaces) {
|
|
||||||
curPath /= "+" + subdir;
|
|
||||||
if(!is_directory(curPath))
|
|
||||||
if(exists("+" + subdir))
|
|
||||||
throw OutputError("Need to write files to directory " + curPath.string() + ", which already exists as a file but is not a directory");
|
|
||||||
else
|
|
||||||
boost::filesystem::create_directory(curPath);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
// open destination classFile
|
// open destination classFile
|
||||||
string classFile = toolboxPath;
|
string classFile = toolboxPath;
|
||||||
|
|
@ -91,7 +79,7 @@ void Class::matlab_proxy(const string& toolboxPath, const string& wrapperName,
|
||||||
const int id = (int)functionNames.size();
|
const int id = (int)functionNames.size();
|
||||||
constructor.proxy_fragment(proxyFile, wrapperName, !qualifiedParent.empty(), id, a);
|
constructor.proxy_fragment(proxyFile, wrapperName, !qualifiedParent.empty(), id, a);
|
||||||
const string wrapFunctionName = constructor.wrapper_fragment(wrapperFile,
|
const string wrapFunctionName = constructor.wrapper_fragment(wrapperFile,
|
||||||
cppName, matlabUniqueName, cppBaseName, id, using_namespaces, a);
|
cppName, matlabUniqueName, cppBaseName, id, a);
|
||||||
wrapperFile.oss << "\n";
|
wrapperFile.oss << "\n";
|
||||||
functionNames.push_back(wrapFunctionName);
|
functionNames.push_back(wrapFunctionName);
|
||||||
}
|
}
|
||||||
|
|
@ -108,7 +96,7 @@ void Class::matlab_proxy(const string& toolboxPath, const string& wrapperName,
|
||||||
const int id = (int)functionNames.size();
|
const int id = (int)functionNames.size();
|
||||||
deconstructor.proxy_fragment(proxyFile, wrapperName, matlabUniqueName, id);
|
deconstructor.proxy_fragment(proxyFile, wrapperName, matlabUniqueName, id);
|
||||||
proxyFile.oss << "\n";
|
proxyFile.oss << "\n";
|
||||||
const string functionName = deconstructor.wrapper_fragment(wrapperFile, cppName, matlabUniqueName, id, using_namespaces);
|
const string functionName = deconstructor.wrapper_fragment(wrapperFile, cppName, matlabUniqueName, id);
|
||||||
wrapperFile.oss << "\n";
|
wrapperFile.oss << "\n";
|
||||||
functionNames.push_back(functionName);
|
functionNames.push_back(functionName);
|
||||||
}
|
}
|
||||||
|
|
@ -118,7 +106,7 @@ void Class::matlab_proxy(const string& toolboxPath, const string& wrapperName,
|
||||||
// Methods
|
// Methods
|
||||||
BOOST_FOREACH(const Methods::value_type& name_m, methods) {
|
BOOST_FOREACH(const Methods::value_type& name_m, methods) {
|
||||||
const Method& m = name_m.second;
|
const Method& m = name_m.second;
|
||||||
m.proxy_wrapper_fragments(proxyFile, wrapperFile, cppName, matlabQualName, matlabUniqueName, wrapperName, using_namespaces, typeAttributes, functionNames);
|
m.proxy_wrapper_fragments(proxyFile, wrapperFile, cppName, matlabQualName, matlabUniqueName, wrapperName, typeAttributes, functionNames);
|
||||||
proxyFile.oss << "\n";
|
proxyFile.oss << "\n";
|
||||||
wrapperFile.oss << "\n";
|
wrapperFile.oss << "\n";
|
||||||
}
|
}
|
||||||
|
|
@ -130,7 +118,7 @@ void Class::matlab_proxy(const string& toolboxPath, const string& wrapperName,
|
||||||
// Static methods
|
// Static methods
|
||||||
BOOST_FOREACH(const StaticMethods::value_type& name_m, static_methods) {
|
BOOST_FOREACH(const StaticMethods::value_type& name_m, static_methods) {
|
||||||
const StaticMethod& m = name_m.second;
|
const StaticMethod& m = name_m.second;
|
||||||
m.proxy_wrapper_fragments(proxyFile, wrapperFile, cppName, matlabQualName, matlabUniqueName, wrapperName, using_namespaces, typeAttributes, functionNames);
|
m.proxy_wrapper_fragments(proxyFile, wrapperFile, cppName, matlabQualName, matlabUniqueName, wrapperName, typeAttributes, functionNames);
|
||||||
proxyFile.oss << "\n";
|
proxyFile.oss << "\n";
|
||||||
wrapperFile.oss << "\n";
|
wrapperFile.oss << "\n";
|
||||||
}
|
}
|
||||||
|
|
@ -195,7 +183,6 @@ void Class::pointer_constructor_fragments(FileWriter& proxyFile, FileWriter& wra
|
||||||
wrapperFile.oss << "void " << collectorInsertFunctionName << "(int nargout, mxArray *out[], int nargin, const mxArray *in[])" << endl;
|
wrapperFile.oss << "void " << collectorInsertFunctionName << "(int nargout, mxArray *out[], int nargin, const mxArray *in[])" << endl;
|
||||||
wrapperFile.oss << "{\n";
|
wrapperFile.oss << "{\n";
|
||||||
wrapperFile.oss << " mexAtExit(&_deleteAllObjects);\n";
|
wrapperFile.oss << " mexAtExit(&_deleteAllObjects);\n";
|
||||||
generateUsingNamespace(wrapperFile, using_namespaces);
|
|
||||||
// Typedef boost::shared_ptr
|
// Typedef boost::shared_ptr
|
||||||
wrapperFile.oss << " typedef boost::shared_ptr<" << cppName << "> Shared;\n";
|
wrapperFile.oss << " typedef boost::shared_ptr<" << cppName << "> Shared;\n";
|
||||||
wrapperFile.oss << "\n";
|
wrapperFile.oss << "\n";
|
||||||
|
|
@ -285,7 +272,6 @@ Class expandClassTemplate(const Class& cls, const string& templateArg, const vec
|
||||||
inst.methods = expandMethodTemplate(cls.methods, templateArg, instName);
|
inst.methods = expandMethodTemplate(cls.methods, templateArg, instName);
|
||||||
inst.static_methods = expandMethodTemplate(cls.static_methods, templateArg, instName);
|
inst.static_methods = expandMethodTemplate(cls.static_methods, templateArg, instName);
|
||||||
inst.namespaces = cls.namespaces;
|
inst.namespaces = cls.namespaces;
|
||||||
inst.using_namespaces = cls.using_namespaces;
|
|
||||||
inst.constructor = cls.constructor;
|
inst.constructor = cls.constructor;
|
||||||
inst.constructor.args_list = expandArgumentListsTemplate(cls.constructor.args_list, templateArg, instName);
|
inst.constructor.args_list = expandArgumentListsTemplate(cls.constructor.args_list, templateArg, instName);
|
||||||
inst.constructor.name = inst.name;
|
inst.constructor.name = inst.name;
|
||||||
|
|
@ -320,7 +306,7 @@ std::string Class::getTypedef() const {
|
||||||
result += ("namespace " + namesp + " { ");
|
result += ("namespace " + namesp + " { ");
|
||||||
}
|
}
|
||||||
result += ("typedef " + typedefName + " " + name + ";");
|
result += ("typedef " + typedefName + " " + name + ";");
|
||||||
BOOST_FOREACH(const string& namesp, namespaces) {
|
for (size_t i = 0; i<namespaces.size(); ++i) {
|
||||||
result += " }";
|
result += " }";
|
||||||
}
|
}
|
||||||
return result;
|
return result;
|
||||||
|
|
|
||||||
|
|
@ -47,7 +47,6 @@ struct Class {
|
||||||
Methods methods; ///< Class methods
|
Methods methods; ///< Class methods
|
||||||
StaticMethods static_methods; ///< Static methods
|
StaticMethods static_methods; ///< Static methods
|
||||||
std::vector<std::string> namespaces; ///< Stack of namespaces
|
std::vector<std::string> namespaces; ///< Stack of namespaces
|
||||||
std::vector<std::string> using_namespaces;///< default namespaces
|
|
||||||
Constructor constructor; ///< Class constructors
|
Constructor constructor; ///< Class constructors
|
||||||
Deconstructor deconstructor; ///< Deconstructor to deallocate C++ object
|
Deconstructor deconstructor; ///< Deconstructor to deallocate C++ object
|
||||||
bool verbose_; ///< verbose flag
|
bool verbose_; ///< verbose flag
|
||||||
|
|
|
||||||
|
|
@ -70,7 +70,6 @@ string Constructor::wrapper_fragment(FileWriter& file,
|
||||||
const string& matlabUniqueName,
|
const string& matlabUniqueName,
|
||||||
const string& cppBaseClassName,
|
const string& cppBaseClassName,
|
||||||
int id,
|
int id,
|
||||||
const vector<string>& using_namespaces,
|
|
||||||
const ArgumentList& al) const {
|
const ArgumentList& al) const {
|
||||||
|
|
||||||
const string wrapFunctionName = matlabUniqueName + "_constructor_" + boost::lexical_cast<string>(id);
|
const string wrapFunctionName = matlabUniqueName + "_constructor_" + boost::lexical_cast<string>(id);
|
||||||
|
|
@ -78,7 +77,6 @@ string Constructor::wrapper_fragment(FileWriter& file,
|
||||||
file.oss << "void " << wrapFunctionName << "(int nargout, mxArray *out[], int nargin, const mxArray *in[])" << endl;
|
file.oss << "void " << wrapFunctionName << "(int nargout, mxArray *out[], int nargin, const mxArray *in[])" << endl;
|
||||||
file.oss << "{\n";
|
file.oss << "{\n";
|
||||||
file.oss << " mexAtExit(&_deleteAllObjects);\n";
|
file.oss << " mexAtExit(&_deleteAllObjects);\n";
|
||||||
generateUsingNamespace(file, using_namespaces);
|
|
||||||
//Typedef boost::shared_ptr
|
//Typedef boost::shared_ptr
|
||||||
file.oss << " typedef boost::shared_ptr<" << cppClassName << "> Shared;\n";
|
file.oss << " typedef boost::shared_ptr<" << cppClassName << "> Shared;\n";
|
||||||
file.oss << "\n";
|
file.oss << "\n";
|
||||||
|
|
|
||||||
|
|
@ -58,7 +58,6 @@ struct Constructor {
|
||||||
const std::string& matlabUniqueName,
|
const std::string& matlabUniqueName,
|
||||||
const std::string& cppBaseClassName,
|
const std::string& cppBaseClassName,
|
||||||
int id,
|
int id,
|
||||||
const std::vector<std::string>& using_namespaces,
|
|
||||||
const ArgumentList& al) const;
|
const ArgumentList& al) const;
|
||||||
|
|
||||||
/// constructor function
|
/// constructor function
|
||||||
|
|
|
||||||
|
|
@ -48,8 +48,7 @@ void Deconstructor::proxy_fragment(FileWriter& file,
|
||||||
string Deconstructor::wrapper_fragment(FileWriter& file,
|
string Deconstructor::wrapper_fragment(FileWriter& file,
|
||||||
const string& cppClassName,
|
const string& cppClassName,
|
||||||
const string& matlabUniqueName,
|
const string& matlabUniqueName,
|
||||||
int id,
|
int id) const {
|
||||||
const vector<string>& using_namespaces) const {
|
|
||||||
|
|
||||||
const string matlabName = matlab_wrapper_name(matlabUniqueName);
|
const string matlabName = matlab_wrapper_name(matlabUniqueName);
|
||||||
|
|
||||||
|
|
@ -57,7 +56,6 @@ string Deconstructor::wrapper_fragment(FileWriter& file,
|
||||||
|
|
||||||
file.oss << "void " << wrapFunctionName << "(int nargout, mxArray *out[], int nargin, const mxArray *in[])" << endl;
|
file.oss << "void " << wrapFunctionName << "(int nargout, mxArray *out[], int nargin, const mxArray *in[])" << endl;
|
||||||
file.oss << "{" << endl;
|
file.oss << "{" << endl;
|
||||||
generateUsingNamespace(file, using_namespaces);
|
|
||||||
file.oss << " typedef boost::shared_ptr<" << cppClassName << "> Shared;" << endl;
|
file.oss << " typedef boost::shared_ptr<" << cppClassName << "> Shared;" << endl;
|
||||||
//Deconstructor takes 1 arg, the mxArray obj
|
//Deconstructor takes 1 arg, the mxArray obj
|
||||||
file.oss << " checkArguments(\"" << matlabName << "\",nargout,nargin," << "1" << ");" << endl;
|
file.oss << " checkArguments(\"" << matlabName << "\",nargout,nargin," << "1" << ");" << endl;
|
||||||
|
|
|
||||||
|
|
@ -54,8 +54,7 @@ struct Deconstructor {
|
||||||
std::string wrapper_fragment(FileWriter& file,
|
std::string wrapper_fragment(FileWriter& file,
|
||||||
const std::string& cppClassName,
|
const std::string& cppClassName,
|
||||||
const std::string& matlabUniqueName,
|
const std::string& matlabUniqueName,
|
||||||
int id,
|
int id) const;
|
||||||
const std::vector<std::string>& using_namespaces) const;
|
|
||||||
};
|
};
|
||||||
|
|
||||||
} // \namespace wrap
|
} // \namespace wrap
|
||||||
|
|
|
||||||
|
|
@ -0,0 +1,161 @@
|
||||||
|
/**
|
||||||
|
* @file GlobalFunction.cpp
|
||||||
|
*
|
||||||
|
* @date Jul 22, 2012
|
||||||
|
* @author Alex Cunningham
|
||||||
|
*/
|
||||||
|
|
||||||
|
#include "GlobalFunction.h"
|
||||||
|
#include "utilities.h"
|
||||||
|
|
||||||
|
#include <boost/foreach.hpp>
|
||||||
|
#include <boost/lexical_cast.hpp>
|
||||||
|
|
||||||
|
namespace wrap {
|
||||||
|
|
||||||
|
using namespace std;
|
||||||
|
|
||||||
|
/* ************************************************************************* */
|
||||||
|
void GlobalFunction::addOverload(bool verbose, const std::string& name,
|
||||||
|
const ArgumentList& args, const ReturnValue& retVal, const StrVec& ns_stack) {
|
||||||
|
this->verbose_ = verbose;
|
||||||
|
this->name = name;
|
||||||
|
this->argLists.push_back(args);
|
||||||
|
this->returnVals.push_back(retVal);
|
||||||
|
this->namespaces.push_back(ns_stack);
|
||||||
|
}
|
||||||
|
|
||||||
|
/* ************************************************************************* */
|
||||||
|
void GlobalFunction::matlab_proxy(const std::string& toolboxPath, const std::string& wrapperName,
|
||||||
|
const TypeAttributesTable& typeAttributes, FileWriter& wrapperFile,
|
||||||
|
std::vector<std::string>& functionNames) const {
|
||||||
|
|
||||||
|
// cluster overloads with same namespace
|
||||||
|
// create new GlobalFunction structures around namespaces - same namespaces and names are overloads
|
||||||
|
// map of namespace to global function
|
||||||
|
typedef map<string, GlobalFunction> GlobalFunctionMap;
|
||||||
|
GlobalFunctionMap grouped_functions;
|
||||||
|
for (size_t i=0; i<namespaces.size(); ++i) {
|
||||||
|
StrVec ns = namespaces.at(i);
|
||||||
|
string str_ns = qualifiedName("", ns, "");
|
||||||
|
ReturnValue ret = returnVals.at(i);
|
||||||
|
ArgumentList args = argLists.at(i);
|
||||||
|
|
||||||
|
if (!grouped_functions.count(str_ns))
|
||||||
|
grouped_functions[str_ns] = GlobalFunction(name, verbose_);
|
||||||
|
|
||||||
|
grouped_functions[str_ns].argLists.push_back(args);
|
||||||
|
grouped_functions[str_ns].returnVals.push_back(ret);
|
||||||
|
grouped_functions[str_ns].namespaces.push_back(ns);
|
||||||
|
}
|
||||||
|
|
||||||
|
size_t lastcheck = grouped_functions.size();
|
||||||
|
BOOST_FOREACH(const GlobalFunctionMap::value_type& p, grouped_functions) {
|
||||||
|
p.second.generateSingleFunction(toolboxPath, wrapperName, typeAttributes, wrapperFile, functionNames);
|
||||||
|
if (--lastcheck != 0)
|
||||||
|
wrapperFile.oss << endl;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
/* ************************************************************************* */
|
||||||
|
void GlobalFunction::generateSingleFunction(const std::string& toolboxPath, const std::string& wrapperName,
|
||||||
|
const TypeAttributesTable& typeAttributes, FileWriter& wrapperFile,
|
||||||
|
std::vector<std::string>& functionNames) const {
|
||||||
|
|
||||||
|
// create the folder for the namespace
|
||||||
|
const StrVec& ns = namespaces.front();
|
||||||
|
createNamespaceStructure(ns, toolboxPath);
|
||||||
|
|
||||||
|
// open destination mfunctionFileName
|
||||||
|
string mfunctionFileName = toolboxPath;
|
||||||
|
if(!ns.empty())
|
||||||
|
mfunctionFileName += "/+" + wrap::qualifiedName("/+", ns);
|
||||||
|
mfunctionFileName += "/" + name + ".m";
|
||||||
|
FileWriter mfunctionFile(mfunctionFileName, verbose_, "%");
|
||||||
|
|
||||||
|
// get the name of actual matlab object
|
||||||
|
const string
|
||||||
|
matlabQualName = qualifiedName(".", ns, name),
|
||||||
|
matlabUniqueName = qualifiedName("", ns, name),
|
||||||
|
cppName = qualifiedName("::", ns, name);
|
||||||
|
|
||||||
|
mfunctionFile.oss << "function varargout = " << name << "(varargin)\n";
|
||||||
|
|
||||||
|
for(size_t overload = 0; overload < argLists.size(); ++overload) {
|
||||||
|
const ArgumentList& args = argLists[overload];
|
||||||
|
const ReturnValue& returnVal = returnVals[overload];
|
||||||
|
size_t nrArgs = args.size();
|
||||||
|
|
||||||
|
const int id = functionNames.size();
|
||||||
|
|
||||||
|
// Output proxy matlab code
|
||||||
|
|
||||||
|
// check for number of arguments...
|
||||||
|
mfunctionFile.oss << (overload==0?"":"else") << "if length(varargin) == " << nrArgs;
|
||||||
|
if (nrArgs>0) mfunctionFile.oss << " && ";
|
||||||
|
// ...and their types
|
||||||
|
bool first = true;
|
||||||
|
for(size_t i=0;i<nrArgs;i++) {
|
||||||
|
if (!first) mfunctionFile.oss << " && ";
|
||||||
|
mfunctionFile.oss << "isa(varargin{" << i+1 << "},'" << args[i].matlabClass(".") << "')";
|
||||||
|
first=false;
|
||||||
|
}
|
||||||
|
mfunctionFile.oss << "\n";
|
||||||
|
|
||||||
|
// output call to C++ wrapper
|
||||||
|
string output;
|
||||||
|
if(returnVal.isPair)
|
||||||
|
output = "[ varargout{1} varargout{2} ] = ";
|
||||||
|
else if(returnVal.category1 == ReturnValue::VOID)
|
||||||
|
output = "";
|
||||||
|
else
|
||||||
|
output = "varargout{1} = ";
|
||||||
|
mfunctionFile.oss << " " << output << wrapperName << "(" << id << ", varargin{:});\n";
|
||||||
|
|
||||||
|
// Output C++ wrapper code
|
||||||
|
|
||||||
|
const string wrapFunctionName = matlabUniqueName + "_" + boost::lexical_cast<string>(id);
|
||||||
|
|
||||||
|
// call
|
||||||
|
wrapperFile.oss << "void " << wrapFunctionName << "(int nargout, mxArray *out[], int nargin, const mxArray *in[])\n";
|
||||||
|
// start
|
||||||
|
wrapperFile.oss << "{\n";
|
||||||
|
|
||||||
|
returnVal.wrapTypeUnwrap(wrapperFile);
|
||||||
|
|
||||||
|
// check arguments
|
||||||
|
// NOTE: for static functions, there is no object passed
|
||||||
|
wrapperFile.oss << " checkArguments(\"" << matlabUniqueName << "\",nargout,nargin," << args.size() << ");\n";
|
||||||
|
|
||||||
|
// unwrap arguments, see Argument.cpp
|
||||||
|
args.matlab_unwrap(wrapperFile,0); // We start at 0 because there is no self object
|
||||||
|
|
||||||
|
// call method with default type and wrap result
|
||||||
|
if (returnVal.type1!="void")
|
||||||
|
returnVal.wrap_result(cppName+"("+args.names()+")", wrapperFile, typeAttributes);
|
||||||
|
else
|
||||||
|
wrapperFile.oss << cppName+"("+args.names()+");\n";
|
||||||
|
|
||||||
|
// finish
|
||||||
|
wrapperFile.oss << "}\n";
|
||||||
|
|
||||||
|
// Add to function list
|
||||||
|
functionNames.push_back(wrapFunctionName);
|
||||||
|
}
|
||||||
|
|
||||||
|
mfunctionFile.oss << "else\n";
|
||||||
|
mfunctionFile.oss << " error('Arguments do not match any overload of function " << matlabQualName << "');" << endl;
|
||||||
|
mfunctionFile.oss << "end" << endl;
|
||||||
|
|
||||||
|
// Close file
|
||||||
|
mfunctionFile.emit(true);
|
||||||
|
}
|
||||||
|
|
||||||
|
/* ************************************************************************* */
|
||||||
|
|
||||||
|
|
||||||
|
} // \namespace wrap
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
@ -0,0 +1,58 @@
|
||||||
|
/**
|
||||||
|
* @file GlobalFunction.h
|
||||||
|
*
|
||||||
|
* @brief Implements codegen for a global function wrapped in matlab
|
||||||
|
*
|
||||||
|
* @date Jul 22, 2012
|
||||||
|
* @author Alex Cunningham
|
||||||
|
*/
|
||||||
|
|
||||||
|
#pragma once
|
||||||
|
|
||||||
|
#include "Argument.h"
|
||||||
|
#include "ReturnValue.h"
|
||||||
|
|
||||||
|
namespace wrap {
|
||||||
|
|
||||||
|
struct GlobalFunction {
|
||||||
|
|
||||||
|
typedef std::vector<std::string> StrVec;
|
||||||
|
|
||||||
|
bool verbose_;
|
||||||
|
std::string name;
|
||||||
|
|
||||||
|
// each overload, regardless of namespace
|
||||||
|
std::vector<ArgumentList> argLists; ///< arugments for each overload
|
||||||
|
std::vector<ReturnValue> returnVals; ///< returnVals for each overload
|
||||||
|
std::vector<StrVec> namespaces; ///< Stack of namespaces
|
||||||
|
|
||||||
|
// Constructor only used in Module
|
||||||
|
GlobalFunction(bool verbose = true) : verbose_(verbose) {}
|
||||||
|
|
||||||
|
// Used to reconstruct
|
||||||
|
GlobalFunction(const std::string& name_, bool verbose = true)
|
||||||
|
: verbose_(verbose), name(name_) {}
|
||||||
|
|
||||||
|
// adds an overloaded version of this function
|
||||||
|
void addOverload(bool verbose, const std::string& name,
|
||||||
|
const ArgumentList& args, const ReturnValue& retVal, const StrVec& ns_stack);
|
||||||
|
|
||||||
|
// codegen function called from Module to build the cpp and matlab versions of the function
|
||||||
|
void matlab_proxy(const std::string& toolboxPath, const std::string& wrapperName,
|
||||||
|
const TypeAttributesTable& typeAttributes, FileWriter& wrapperFile,
|
||||||
|
std::vector<std::string>& functionNames) const;
|
||||||
|
|
||||||
|
private:
|
||||||
|
|
||||||
|
// Creates a single global function - all in same namespace
|
||||||
|
void generateSingleFunction(const std::string& toolboxPath, const std::string& wrapperName,
|
||||||
|
const TypeAttributesTable& typeAttributes, FileWriter& wrapperFile,
|
||||||
|
std::vector<std::string>& functionNames) const;
|
||||||
|
|
||||||
|
};
|
||||||
|
|
||||||
|
} // \namespace wrap
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
@ -42,7 +42,6 @@ void Method::proxy_wrapper_fragments(FileWriter& proxyFile, FileWriter& wrapperF
|
||||||
const std::string& matlabQualName,
|
const std::string& matlabQualName,
|
||||||
const std::string& matlabUniqueName,
|
const std::string& matlabUniqueName,
|
||||||
const string& wrapperName,
|
const string& wrapperName,
|
||||||
const vector<string>& using_namespaces,
|
|
||||||
const TypeAttributesTable& typeAttributes,
|
const TypeAttributesTable& typeAttributes,
|
||||||
vector<string>& functionNames) const {
|
vector<string>& functionNames) const {
|
||||||
|
|
||||||
|
|
@ -82,7 +81,7 @@ void Method::proxy_wrapper_fragments(FileWriter& proxyFile, FileWriter& wrapperF
|
||||||
// Output C++ wrapper code
|
// Output C++ wrapper code
|
||||||
|
|
||||||
const string wrapFunctionName = wrapper_fragment(
|
const string wrapFunctionName = wrapper_fragment(
|
||||||
wrapperFile, cppClassName, matlabUniqueName, overload, id, using_namespaces, typeAttributes);
|
wrapperFile, cppClassName, matlabUniqueName, overload, id, typeAttributes);
|
||||||
|
|
||||||
// Add to function list
|
// Add to function list
|
||||||
functionNames.push_back(wrapFunctionName);
|
functionNames.push_back(wrapFunctionName);
|
||||||
|
|
@ -103,7 +102,6 @@ string Method::wrapper_fragment(FileWriter& file,
|
||||||
const string& matlabUniqueName,
|
const string& matlabUniqueName,
|
||||||
int overload,
|
int overload,
|
||||||
int id,
|
int id,
|
||||||
const vector<string>& using_namespaces,
|
|
||||||
const TypeAttributesTable& typeAttributes) const {
|
const TypeAttributesTable& typeAttributes) const {
|
||||||
|
|
||||||
// generate code
|
// generate code
|
||||||
|
|
@ -117,7 +115,6 @@ string Method::wrapper_fragment(FileWriter& file,
|
||||||
file.oss << "void " << wrapFunctionName << "(int nargout, mxArray *out[], int nargin, const mxArray *in[])\n";
|
file.oss << "void " << wrapFunctionName << "(int nargout, mxArray *out[], int nargin, const mxArray *in[])\n";
|
||||||
// start
|
// start
|
||||||
file.oss << "{\n";
|
file.oss << "{\n";
|
||||||
generateUsingNamespace(file, using_namespaces);
|
|
||||||
|
|
||||||
if(returnVal.isPair)
|
if(returnVal.isPair)
|
||||||
{
|
{
|
||||||
|
|
|
||||||
|
|
@ -51,8 +51,7 @@ struct Method {
|
||||||
// classPath is class directory, e.g., ../matlab/@Point2
|
// classPath is class directory, e.g., ../matlab/@Point2
|
||||||
void proxy_wrapper_fragments(FileWriter& proxyFile, FileWriter& wrapperFile,
|
void proxy_wrapper_fragments(FileWriter& proxyFile, FileWriter& wrapperFile,
|
||||||
const std::string& cppClassName, const std::string& matlabQualName, const std::string& matlabUniqueName,
|
const std::string& cppClassName, const std::string& matlabQualName, const std::string& matlabUniqueName,
|
||||||
const std::string& wrapperName, const std::vector<std::string>& using_namespaces,
|
const std::string& wrapperName, const TypeAttributesTable& typeAttributes,
|
||||||
const TypeAttributesTable& typeAttributes,
|
|
||||||
std::vector<std::string>& functionNames) const;
|
std::vector<std::string>& functionNames) const;
|
||||||
|
|
||||||
private:
|
private:
|
||||||
|
|
@ -61,7 +60,6 @@ private:
|
||||||
const std::string& matlabUniqueName,
|
const std::string& matlabUniqueName,
|
||||||
int overload,
|
int overload,
|
||||||
int id,
|
int id,
|
||||||
const std::vector<std::string>& using_namespaces,
|
|
||||||
const TypeAttributesTable& typeAttributes) const; ///< cpp wrapper
|
const TypeAttributesTable& typeAttributes) const; ///< cpp wrapper
|
||||||
};
|
};
|
||||||
|
|
||||||
|
|
|
||||||
|
|
@ -79,13 +79,12 @@ Module::Module(const string& interfacePath,
|
||||||
vector<string> arg_dup; ///keep track of duplicates
|
vector<string> arg_dup; ///keep track of duplicates
|
||||||
Constructor constructor0(enable_verbose), constructor(enable_verbose);
|
Constructor constructor0(enable_verbose), constructor(enable_verbose);
|
||||||
Deconstructor deconstructor0(enable_verbose), deconstructor(enable_verbose);
|
Deconstructor deconstructor0(enable_verbose), deconstructor(enable_verbose);
|
||||||
//Method method0(enable_verbose), method(enable_verbose);
|
|
||||||
StaticMethod static_method0(enable_verbose), static_method(enable_verbose);
|
StaticMethod static_method0(enable_verbose), static_method(enable_verbose);
|
||||||
Class cls0(enable_verbose),cls(enable_verbose);
|
Class cls0(enable_verbose),cls(enable_verbose);
|
||||||
ForwardDeclaration fwDec0, fwDec;
|
GlobalFunction globalFunc0(enable_verbose), globalFunc(enable_verbose);
|
||||||
|
ForwardDeclaration fwDec0, fwDec;
|
||||||
vector<string> namespaces, /// current namespace tag
|
vector<string> namespaces, /// current namespace tag
|
||||||
namespaces_return, /// namespace for current return type
|
namespaces_return; /// namespace for current return type
|
||||||
using_namespace_current; /// All namespaces from "using" declarations
|
|
||||||
string templateArgument;
|
string templateArgument;
|
||||||
vector<string> templateInstantiationNamespace;
|
vector<string> templateInstantiationNamespace;
|
||||||
vector<vector<string> > templateInstantiations;
|
vector<vector<string> > templateInstantiations;
|
||||||
|
|
@ -261,12 +260,11 @@ Module::Module(const string& interfacePath,
|
||||||
>> ((':' >> classParent_p >> '{') | '{')
|
>> ((':' >> classParent_p >> '{') | '{')
|
||||||
>> *(functions_p | comments_p)
|
>> *(functions_p | comments_p)
|
||||||
>> str_p("};"))
|
>> str_p("};"))
|
||||||
[assign_a(constructor.name, cls.name)]
|
[assign_a(constructor.name, cls.name)]
|
||||||
[assign_a(cls.constructor, constructor)]
|
[assign_a(cls.constructor, constructor)]
|
||||||
[assign_a(cls.namespaces, namespaces)]
|
[assign_a(cls.namespaces, namespaces)]
|
||||||
[assign_a(cls.using_namespaces, using_namespace_current)]
|
[assign_a(deconstructor.name,cls.name)]
|
||||||
[assign_a(deconstructor.name,cls.name)]
|
[assign_a(cls.deconstructor, deconstructor)]
|
||||||
[assign_a(cls.deconstructor, deconstructor)]
|
|
||||||
[bl::bind(&handle_possible_template, bl::var(classes), bl::var(cls), bl::var(templateArgument), bl::var(templateInstantiations))]
|
[bl::bind(&handle_possible_template, bl::var(classes), bl::var(cls), bl::var(templateArgument), bl::var(templateInstantiations))]
|
||||||
[assign_a(deconstructor,deconstructor0)]
|
[assign_a(deconstructor,deconstructor0)]
|
||||||
[assign_a(constructor, constructor0)]
|
[assign_a(constructor, constructor0)]
|
||||||
|
|
@ -274,21 +272,30 @@ Module::Module(const string& interfacePath,
|
||||||
[clear_a(templateArgument)]
|
[clear_a(templateArgument)]
|
||||||
[clear_a(templateInstantiations)];
|
[clear_a(templateInstantiations)];
|
||||||
|
|
||||||
|
Rule global_function_p =
|
||||||
|
(returnType_p >> staticMethodName_p[assign_a(methodName)] >>
|
||||||
|
'(' >> argumentList_p >> ')' >> ';' >> *comments_p)
|
||||||
|
[bl::bind(&GlobalFunction::addOverload,
|
||||||
|
bl::var(global_functions)[bl::var(methodName)],
|
||||||
|
verbose,
|
||||||
|
bl::var(methodName),
|
||||||
|
bl::var(args),
|
||||||
|
bl::var(retVal),
|
||||||
|
bl::var(namespaces))]
|
||||||
|
[assign_a(methodName,methodName0)]
|
||||||
|
[assign_a(args,args0)]
|
||||||
|
[assign_a(retVal,retVal0)];
|
||||||
|
|
||||||
Rule include_p = str_p("#include") >> ch_p('<') >> (*(anychar_p - '>'))[push_back_a(includes)] >> ch_p('>');
|
Rule include_p = str_p("#include") >> ch_p('<') >> (*(anychar_p - '>'))[push_back_a(includes)] >> ch_p('>');
|
||||||
|
|
||||||
Rule namespace_def_p =
|
Rule namespace_def_p =
|
||||||
(str_p("namespace")
|
(str_p("namespace")
|
||||||
>> namespace_name_p[push_back_a(namespaces)]
|
>> namespace_name_p[push_back_a(namespaces)]
|
||||||
>> ch_p('{')
|
>> ch_p('{')
|
||||||
>> *(include_p | class_p | templateSingleInstantiation_p | namespace_def_p | comments_p)
|
>> *(include_p | class_p | templateSingleInstantiation_p | global_function_p | namespace_def_p | comments_p)
|
||||||
>> str_p("}///\\namespace") // end namespace, avoid confusion with classes
|
>> ch_p('}'))
|
||||||
>> !namespace_name_p)
|
|
||||||
[pop_a(namespaces)];
|
[pop_a(namespaces)];
|
||||||
|
|
||||||
Rule using_namespace_p =
|
|
||||||
str_p("using") >> str_p("namespace")
|
|
||||||
>> namespace_name_p[push_back_a(using_namespace_current)] >> ch_p(';');
|
|
||||||
|
|
||||||
Rule forward_declaration_p =
|
Rule forward_declaration_p =
|
||||||
!(str_p("virtual")[assign_a(fwDec.isVirtual, true)])
|
!(str_p("virtual")[assign_a(fwDec.isVirtual, true)])
|
||||||
>> str_p("class")
|
>> str_p("class")
|
||||||
|
|
@ -297,7 +304,7 @@ Module::Module(const string& interfacePath,
|
||||||
[push_back_a(forward_declarations, fwDec)]
|
[push_back_a(forward_declarations, fwDec)]
|
||||||
[assign_a(fwDec, fwDec0)];
|
[assign_a(fwDec, fwDec0)];
|
||||||
|
|
||||||
Rule module_content_p = comments_p | using_namespace_p | include_p | class_p | templateSingleInstantiation_p | forward_declaration_p | namespace_def_p ;
|
Rule module_content_p = comments_p | include_p | class_p | templateSingleInstantiation_p | forward_declaration_p | global_function_p | namespace_def_p;
|
||||||
|
|
||||||
Rule module_p = *module_content_p >> !end_p;
|
Rule module_p = *module_content_p >> !end_p;
|
||||||
|
|
||||||
|
|
@ -451,6 +458,11 @@ void Module::matlab_code(const string& toolboxPath, const string& headerPath) co
|
||||||
cls.matlab_proxy(toolboxPath, wrapperName, typeAttributes, wrapperFile, functionNames);
|
cls.matlab_proxy(toolboxPath, wrapperName, typeAttributes, wrapperFile, functionNames);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// create matlab files and wrapper code for global functions
|
||||||
|
BOOST_FOREACH(const GlobalFunctions::value_type& p, global_functions) {
|
||||||
|
p.second.matlab_proxy(toolboxPath, wrapperName, typeAttributes, wrapperFile, functionNames);
|
||||||
|
}
|
||||||
|
|
||||||
// finish wrapper file
|
// finish wrapper file
|
||||||
wrapperFile.oss << "\n";
|
wrapperFile.oss << "\n";
|
||||||
finish_wrapper(wrapperFile, functionNames);
|
finish_wrapper(wrapperFile, functionNames);
|
||||||
|
|
|
||||||
|
|
@ -23,6 +23,7 @@
|
||||||
#include <map>
|
#include <map>
|
||||||
|
|
||||||
#include "Class.h"
|
#include "Class.h"
|
||||||
|
#include "GlobalFunction.h"
|
||||||
#include "TemplateInstantiationTypedef.h"
|
#include "TemplateInstantiationTypedef.h"
|
||||||
#include "ForwardDeclaration.h"
|
#include "ForwardDeclaration.h"
|
||||||
|
|
||||||
|
|
@ -33,13 +34,15 @@ namespace wrap {
|
||||||
*/
|
*/
|
||||||
struct Module {
|
struct Module {
|
||||||
|
|
||||||
|
typedef std::map<std::string, GlobalFunction> GlobalFunctions;
|
||||||
|
|
||||||
std::string name; ///< module name
|
std::string name; ///< module name
|
||||||
std::vector<Class> classes; ///< list of classes
|
std::vector<Class> classes; ///< list of classes
|
||||||
std::vector<TemplateInstantiationTypedef> templateInstantiationTypedefs; ///< list of template instantiations
|
std::vector<TemplateInstantiationTypedef> templateInstantiationTypedefs; ///< list of template instantiations
|
||||||
bool verbose; ///< verbose flag
|
bool verbose; ///< verbose flag
|
||||||
// std::vector<std::string> using_namespaces; ///< all default namespaces
|
|
||||||
std::vector<ForwardDeclaration> forward_declarations;
|
std::vector<ForwardDeclaration> forward_declarations;
|
||||||
std::vector<std::string> includes; ///< Include statements
|
std::vector<std::string> includes; ///< Include statements
|
||||||
|
GlobalFunctions global_functions;
|
||||||
|
|
||||||
/// constructor that parses interface file
|
/// constructor that parses interface file
|
||||||
Module(const std::string& interfacePath,
|
Module(const std::string& interfacePath,
|
||||||
|
|
|
||||||
|
|
@ -122,5 +122,19 @@ void ReturnValue::wrap_result(const string& result, FileWriter& file, const Type
|
||||||
}
|
}
|
||||||
|
|
||||||
/* ************************************************************************* */
|
/* ************************************************************************* */
|
||||||
|
void ReturnValue::wrapTypeUnwrap(FileWriter& wrapperFile) const {
|
||||||
|
if(isPair)
|
||||||
|
{
|
||||||
|
if(category1 == ReturnValue::CLASS)
|
||||||
|
wrapperFile.oss << " typedef boost::shared_ptr<" << qualifiedType1("::") << "> Shared" << type1 << ";"<< endl;
|
||||||
|
if(category2 == ReturnValue::CLASS)
|
||||||
|
wrapperFile.oss << " typedef boost::shared_ptr<" << qualifiedType2("::") << "> Shared" << type2 << ";"<< endl;
|
||||||
|
}
|
||||||
|
else {
|
||||||
|
if (category1 == ReturnValue::CLASS)
|
||||||
|
wrapperFile.oss << " typedef boost::shared_ptr<" << qualifiedType1("::") << "> Shared" << type1 << ";"<< endl;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
/* ************************************************************************* */
|
||||||
|
|
||||||
|
|
||||||
|
|
|
||||||
|
|
@ -52,6 +52,8 @@ struct ReturnValue {
|
||||||
|
|
||||||
void wrap_result(const std::string& result, FileWriter& file, const TypeAttributesTable& typeAttributes) const;
|
void wrap_result(const std::string& result, FileWriter& file, const TypeAttributesTable& typeAttributes) const;
|
||||||
|
|
||||||
|
void wrapTypeUnwrap(FileWriter& wrapperFile) const;
|
||||||
|
|
||||||
};
|
};
|
||||||
|
|
||||||
} // \namespace wrap
|
} // \namespace wrap
|
||||||
|
|
|
||||||
|
|
@ -38,12 +38,12 @@ void StaticMethod::addOverload(bool verbose, const std::string& name,
|
||||||
this->returnVals.push_back(retVal);
|
this->returnVals.push_back(retVal);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
/* ************************************************************************* */
|
||||||
void StaticMethod::proxy_wrapper_fragments(FileWriter& proxyFile, FileWriter& wrapperFile,
|
void StaticMethod::proxy_wrapper_fragments(FileWriter& proxyFile, FileWriter& wrapperFile,
|
||||||
const string& cppClassName,
|
const string& cppClassName,
|
||||||
const std::string& matlabQualName,
|
const std::string& matlabQualName,
|
||||||
const std::string& matlabUniqueName,
|
const std::string& matlabUniqueName,
|
||||||
const string& wrapperName,
|
const string& wrapperName,
|
||||||
const vector<string>& using_namespaces,
|
|
||||||
const TypeAttributesTable& typeAttributes,
|
const TypeAttributesTable& typeAttributes,
|
||||||
vector<string>& functionNames) const {
|
vector<string>& functionNames) const {
|
||||||
|
|
||||||
|
|
@ -85,7 +85,7 @@ void StaticMethod::proxy_wrapper_fragments(FileWriter& proxyFile, FileWriter& wr
|
||||||
// Output C++ wrapper code
|
// Output C++ wrapper code
|
||||||
|
|
||||||
const string wrapFunctionName = wrapper_fragment(
|
const string wrapFunctionName = wrapper_fragment(
|
||||||
wrapperFile, cppClassName, matlabUniqueName, overload, id, using_namespaces, typeAttributes);
|
wrapperFile, cppClassName, matlabUniqueName, overload, id, typeAttributes);
|
||||||
|
|
||||||
// Add to function list
|
// Add to function list
|
||||||
functionNames.push_back(wrapFunctionName);
|
functionNames.push_back(wrapFunctionName);
|
||||||
|
|
@ -106,7 +106,6 @@ string StaticMethod::wrapper_fragment(FileWriter& file,
|
||||||
const string& matlabUniqueName,
|
const string& matlabUniqueName,
|
||||||
int overload,
|
int overload,
|
||||||
int id,
|
int id,
|
||||||
const vector<string>& using_namespaces,
|
|
||||||
const TypeAttributesTable& typeAttributes) const {
|
const TypeAttributesTable& typeAttributes) const {
|
||||||
|
|
||||||
// generate code
|
// generate code
|
||||||
|
|
@ -120,18 +119,8 @@ string StaticMethod::wrapper_fragment(FileWriter& file,
|
||||||
file.oss << "void " << wrapFunctionName << "(int nargout, mxArray *out[], int nargin, const mxArray *in[])\n";
|
file.oss << "void " << wrapFunctionName << "(int nargout, mxArray *out[], int nargin, const mxArray *in[])\n";
|
||||||
// start
|
// start
|
||||||
file.oss << "{\n";
|
file.oss << "{\n";
|
||||||
generateUsingNamespace(file, using_namespaces);
|
|
||||||
|
|
||||||
if(returnVal.isPair)
|
returnVal.wrapTypeUnwrap(file);
|
||||||
{
|
|
||||||
if(returnVal.category1 == ReturnValue::CLASS)
|
|
||||||
file.oss << " typedef boost::shared_ptr<" << returnVal.qualifiedType1("::") << "> Shared" << returnVal.type1 << ";"<< endl;
|
|
||||||
if(returnVal.category2 == ReturnValue::CLASS)
|
|
||||||
file.oss << " typedef boost::shared_ptr<" << returnVal.qualifiedType2("::") << "> Shared" << returnVal.type2 << ";"<< endl;
|
|
||||||
}
|
|
||||||
else
|
|
||||||
if(returnVal.category1 == ReturnValue::CLASS)
|
|
||||||
file.oss << " typedef boost::shared_ptr<" << returnVal.qualifiedType1("::") << "> Shared" << returnVal.type1 << ";"<< endl;
|
|
||||||
|
|
||||||
file.oss << " typedef boost::shared_ptr<" << cppClassName << "> Shared;" << endl;
|
file.oss << " typedef boost::shared_ptr<" << cppClassName << "> Shared;" << endl;
|
||||||
|
|
||||||
|
|
|
||||||
|
|
@ -51,8 +51,7 @@ struct StaticMethod {
|
||||||
// classPath is class directory, e.g., ../matlab/@Point2
|
// classPath is class directory, e.g., ../matlab/@Point2
|
||||||
void proxy_wrapper_fragments(FileWriter& proxyFile, FileWriter& wrapperFile,
|
void proxy_wrapper_fragments(FileWriter& proxyFile, FileWriter& wrapperFile,
|
||||||
const std::string& cppClassName, const std::string& matlabQualName, const std::string& matlabUniqueName,
|
const std::string& cppClassName, const std::string& matlabQualName, const std::string& matlabUniqueName,
|
||||||
const std::string& wrapperName, const std::vector<std::string>& using_namespaces,
|
const std::string& wrapperName, const TypeAttributesTable& typeAttributes,
|
||||||
const TypeAttributesTable& typeAttributes,
|
|
||||||
std::vector<std::string>& functionNames) const;
|
std::vector<std::string>& functionNames) const;
|
||||||
|
|
||||||
private:
|
private:
|
||||||
|
|
@ -61,7 +60,6 @@ private:
|
||||||
const std::string& matlabUniqueName,
|
const std::string& matlabUniqueName,
|
||||||
int overload,
|
int overload,
|
||||||
int id,
|
int id,
|
||||||
const std::vector<std::string>& using_namespaces,
|
|
||||||
const TypeAttributesTable& typeAttributes) const; ///< cpp wrapper
|
const TypeAttributesTable& typeAttributes) const; ///< cpp wrapper
|
||||||
};
|
};
|
||||||
|
|
||||||
|
|
|
||||||
|
|
@ -0,0 +1,7 @@
|
||||||
|
% automatically generated by wrap
|
||||||
|
function varargout = aGlobalFunction(varargin)
|
||||||
|
if length(varargin) == 0
|
||||||
|
varargout{1} = geometry_wrapper(40, varargin{:});
|
||||||
|
else
|
||||||
|
error('Arguments do not match any overload of function aGlobalFunction');
|
||||||
|
end
|
||||||
|
|
@ -180,7 +180,6 @@ void Point2_y_10(int nargout, mxArray *out[], int nargin, const mxArray *in[])
|
||||||
void Point3_collectorInsertAndMakeBase_11(int nargout, mxArray *out[], int nargin, const mxArray *in[])
|
void Point3_collectorInsertAndMakeBase_11(int nargout, mxArray *out[], int nargin, const mxArray *in[])
|
||||||
{
|
{
|
||||||
mexAtExit(&_deleteAllObjects);
|
mexAtExit(&_deleteAllObjects);
|
||||||
using namespace geometry;
|
|
||||||
typedef boost::shared_ptr<Point3> Shared;
|
typedef boost::shared_ptr<Point3> Shared;
|
||||||
|
|
||||||
Shared *self = *reinterpret_cast<Shared**> (mxGetData(in[0]));
|
Shared *self = *reinterpret_cast<Shared**> (mxGetData(in[0]));
|
||||||
|
|
@ -190,7 +189,6 @@ using namespace geometry;
|
||||||
void Point3_constructor_12(int nargout, mxArray *out[], int nargin, const mxArray *in[])
|
void Point3_constructor_12(int nargout, mxArray *out[], int nargin, const mxArray *in[])
|
||||||
{
|
{
|
||||||
mexAtExit(&_deleteAllObjects);
|
mexAtExit(&_deleteAllObjects);
|
||||||
using namespace geometry;
|
|
||||||
typedef boost::shared_ptr<Point3> Shared;
|
typedef boost::shared_ptr<Point3> Shared;
|
||||||
|
|
||||||
double x = unwrap< double >(in[0]);
|
double x = unwrap< double >(in[0]);
|
||||||
|
|
@ -204,7 +202,6 @@ using namespace geometry;
|
||||||
|
|
||||||
void Point3_deconstructor_13(int nargout, mxArray *out[], int nargin, const mxArray *in[])
|
void Point3_deconstructor_13(int nargout, mxArray *out[], int nargin, const mxArray *in[])
|
||||||
{
|
{
|
||||||
using namespace geometry;
|
|
||||||
typedef boost::shared_ptr<Point3> Shared;
|
typedef boost::shared_ptr<Point3> Shared;
|
||||||
checkArguments("delete_Point3",nargout,nargin,1);
|
checkArguments("delete_Point3",nargout,nargin,1);
|
||||||
Shared *self = *reinterpret_cast<Shared**>(mxGetData(in[0]));
|
Shared *self = *reinterpret_cast<Shared**>(mxGetData(in[0]));
|
||||||
|
|
@ -218,7 +215,6 @@ using namespace geometry;
|
||||||
|
|
||||||
void Point3_norm_14(int nargout, mxArray *out[], int nargin, const mxArray *in[])
|
void Point3_norm_14(int nargout, mxArray *out[], int nargin, const mxArray *in[])
|
||||||
{
|
{
|
||||||
using namespace geometry;
|
|
||||||
typedef boost::shared_ptr<Point3> Shared;
|
typedef boost::shared_ptr<Point3> Shared;
|
||||||
checkArguments("norm",nargout,nargin-1,0);
|
checkArguments("norm",nargout,nargin-1,0);
|
||||||
Shared obj = unwrap_shared_ptr<Point3>(in[0], "ptr_Point3");
|
Shared obj = unwrap_shared_ptr<Point3>(in[0], "ptr_Point3");
|
||||||
|
|
@ -227,7 +223,6 @@ using namespace geometry;
|
||||||
|
|
||||||
void Point3_StaticFunctionRet_15(int nargout, mxArray *out[], int nargin, const mxArray *in[])
|
void Point3_StaticFunctionRet_15(int nargout, mxArray *out[], int nargin, const mxArray *in[])
|
||||||
{
|
{
|
||||||
using namespace geometry;
|
|
||||||
typedef boost::shared_ptr<Point3> SharedPoint3;
|
typedef boost::shared_ptr<Point3> SharedPoint3;
|
||||||
typedef boost::shared_ptr<Point3> Shared;
|
typedef boost::shared_ptr<Point3> Shared;
|
||||||
checkArguments("Point3.StaticFunctionRet",nargout,nargin,1);
|
checkArguments("Point3.StaticFunctionRet",nargout,nargin,1);
|
||||||
|
|
@ -237,7 +232,6 @@ using namespace geometry;
|
||||||
|
|
||||||
void Point3_staticFunction_16(int nargout, mxArray *out[], int nargin, const mxArray *in[])
|
void Point3_staticFunction_16(int nargout, mxArray *out[], int nargin, const mxArray *in[])
|
||||||
{
|
{
|
||||||
using namespace geometry;
|
|
||||||
typedef boost::shared_ptr<Point3> Shared;
|
typedef boost::shared_ptr<Point3> Shared;
|
||||||
checkArguments("Point3.staticFunction",nargout,nargin,0);
|
checkArguments("Point3.staticFunction",nargout,nargin,0);
|
||||||
out[0] = wrap< double >(Point3::staticFunction());
|
out[0] = wrap< double >(Point3::staticFunction());
|
||||||
|
|
@ -246,7 +240,6 @@ using namespace geometry;
|
||||||
void Test_collectorInsertAndMakeBase_17(int nargout, mxArray *out[], int nargin, const mxArray *in[])
|
void Test_collectorInsertAndMakeBase_17(int nargout, mxArray *out[], int nargin, const mxArray *in[])
|
||||||
{
|
{
|
||||||
mexAtExit(&_deleteAllObjects);
|
mexAtExit(&_deleteAllObjects);
|
||||||
using namespace geometry;
|
|
||||||
typedef boost::shared_ptr<Test> Shared;
|
typedef boost::shared_ptr<Test> Shared;
|
||||||
|
|
||||||
Shared *self = *reinterpret_cast<Shared**> (mxGetData(in[0]));
|
Shared *self = *reinterpret_cast<Shared**> (mxGetData(in[0]));
|
||||||
|
|
@ -256,7 +249,6 @@ using namespace geometry;
|
||||||
void Test_constructor_18(int nargout, mxArray *out[], int nargin, const mxArray *in[])
|
void Test_constructor_18(int nargout, mxArray *out[], int nargin, const mxArray *in[])
|
||||||
{
|
{
|
||||||
mexAtExit(&_deleteAllObjects);
|
mexAtExit(&_deleteAllObjects);
|
||||||
using namespace geometry;
|
|
||||||
typedef boost::shared_ptr<Test> Shared;
|
typedef boost::shared_ptr<Test> Shared;
|
||||||
|
|
||||||
Shared *self = new Shared(new Test());
|
Shared *self = new Shared(new Test());
|
||||||
|
|
@ -268,7 +260,6 @@ using namespace geometry;
|
||||||
void Test_constructor_19(int nargout, mxArray *out[], int nargin, const mxArray *in[])
|
void Test_constructor_19(int nargout, mxArray *out[], int nargin, const mxArray *in[])
|
||||||
{
|
{
|
||||||
mexAtExit(&_deleteAllObjects);
|
mexAtExit(&_deleteAllObjects);
|
||||||
using namespace geometry;
|
|
||||||
typedef boost::shared_ptr<Test> Shared;
|
typedef boost::shared_ptr<Test> Shared;
|
||||||
|
|
||||||
double a = unwrap< double >(in[0]);
|
double a = unwrap< double >(in[0]);
|
||||||
|
|
@ -281,7 +272,6 @@ using namespace geometry;
|
||||||
|
|
||||||
void Test_deconstructor_20(int nargout, mxArray *out[], int nargin, const mxArray *in[])
|
void Test_deconstructor_20(int nargout, mxArray *out[], int nargin, const mxArray *in[])
|
||||||
{
|
{
|
||||||
using namespace geometry;
|
|
||||||
typedef boost::shared_ptr<Test> Shared;
|
typedef boost::shared_ptr<Test> Shared;
|
||||||
checkArguments("delete_Test",nargout,nargin,1);
|
checkArguments("delete_Test",nargout,nargin,1);
|
||||||
Shared *self = *reinterpret_cast<Shared**>(mxGetData(in[0]));
|
Shared *self = *reinterpret_cast<Shared**>(mxGetData(in[0]));
|
||||||
|
|
@ -295,7 +285,6 @@ using namespace geometry;
|
||||||
|
|
||||||
void Test_arg_EigenConstRef_21(int nargout, mxArray *out[], int nargin, const mxArray *in[])
|
void Test_arg_EigenConstRef_21(int nargout, mxArray *out[], int nargin, const mxArray *in[])
|
||||||
{
|
{
|
||||||
using namespace geometry;
|
|
||||||
typedef boost::shared_ptr<Test> Shared;
|
typedef boost::shared_ptr<Test> Shared;
|
||||||
checkArguments("arg_EigenConstRef",nargout,nargin-1,1);
|
checkArguments("arg_EigenConstRef",nargout,nargin-1,1);
|
||||||
Shared obj = unwrap_shared_ptr<Test>(in[0], "ptr_Test");
|
Shared obj = unwrap_shared_ptr<Test>(in[0], "ptr_Test");
|
||||||
|
|
@ -305,7 +294,6 @@ using namespace geometry;
|
||||||
|
|
||||||
void Test_create_MixedPtrs_22(int nargout, mxArray *out[], int nargin, const mxArray *in[])
|
void Test_create_MixedPtrs_22(int nargout, mxArray *out[], int nargin, const mxArray *in[])
|
||||||
{
|
{
|
||||||
using namespace geometry;
|
|
||||||
typedef boost::shared_ptr<Test> SharedTest;
|
typedef boost::shared_ptr<Test> SharedTest;
|
||||||
typedef boost::shared_ptr<Test> SharedTest;
|
typedef boost::shared_ptr<Test> SharedTest;
|
||||||
typedef boost::shared_ptr<Test> Shared;
|
typedef boost::shared_ptr<Test> Shared;
|
||||||
|
|
@ -317,7 +305,6 @@ using namespace geometry;
|
||||||
|
|
||||||
void Test_create_ptrs_23(int nargout, mxArray *out[], int nargin, const mxArray *in[])
|
void Test_create_ptrs_23(int nargout, mxArray *out[], int nargin, const mxArray *in[])
|
||||||
{
|
{
|
||||||
using namespace geometry;
|
|
||||||
typedef boost::shared_ptr<Test> SharedTest;
|
typedef boost::shared_ptr<Test> SharedTest;
|
||||||
typedef boost::shared_ptr<Test> SharedTest;
|
typedef boost::shared_ptr<Test> SharedTest;
|
||||||
typedef boost::shared_ptr<Test> Shared;
|
typedef boost::shared_ptr<Test> Shared;
|
||||||
|
|
@ -329,7 +316,6 @@ using namespace geometry;
|
||||||
|
|
||||||
void Test_print_24(int nargout, mxArray *out[], int nargin, const mxArray *in[])
|
void Test_print_24(int nargout, mxArray *out[], int nargin, const mxArray *in[])
|
||||||
{
|
{
|
||||||
using namespace geometry;
|
|
||||||
typedef boost::shared_ptr<Test> Shared;
|
typedef boost::shared_ptr<Test> Shared;
|
||||||
checkArguments("print",nargout,nargin-1,0);
|
checkArguments("print",nargout,nargin-1,0);
|
||||||
Shared obj = unwrap_shared_ptr<Test>(in[0], "ptr_Test");
|
Shared obj = unwrap_shared_ptr<Test>(in[0], "ptr_Test");
|
||||||
|
|
@ -338,7 +324,6 @@ using namespace geometry;
|
||||||
|
|
||||||
void Test_return_Point2Ptr_25(int nargout, mxArray *out[], int nargin, const mxArray *in[])
|
void Test_return_Point2Ptr_25(int nargout, mxArray *out[], int nargin, const mxArray *in[])
|
||||||
{
|
{
|
||||||
using namespace geometry;
|
|
||||||
typedef boost::shared_ptr<Point2> SharedPoint2;
|
typedef boost::shared_ptr<Point2> SharedPoint2;
|
||||||
typedef boost::shared_ptr<Test> Shared;
|
typedef boost::shared_ptr<Test> Shared;
|
||||||
checkArguments("return_Point2Ptr",nargout,nargin-1,1);
|
checkArguments("return_Point2Ptr",nargout,nargin-1,1);
|
||||||
|
|
@ -349,7 +334,6 @@ using namespace geometry;
|
||||||
|
|
||||||
void Test_return_Test_26(int nargout, mxArray *out[], int nargin, const mxArray *in[])
|
void Test_return_Test_26(int nargout, mxArray *out[], int nargin, const mxArray *in[])
|
||||||
{
|
{
|
||||||
using namespace geometry;
|
|
||||||
typedef boost::shared_ptr<Test> SharedTest;
|
typedef boost::shared_ptr<Test> SharedTest;
|
||||||
typedef boost::shared_ptr<Test> Shared;
|
typedef boost::shared_ptr<Test> Shared;
|
||||||
checkArguments("return_Test",nargout,nargin-1,1);
|
checkArguments("return_Test",nargout,nargin-1,1);
|
||||||
|
|
@ -360,7 +344,6 @@ using namespace geometry;
|
||||||
|
|
||||||
void Test_return_TestPtr_27(int nargout, mxArray *out[], int nargin, const mxArray *in[])
|
void Test_return_TestPtr_27(int nargout, mxArray *out[], int nargin, const mxArray *in[])
|
||||||
{
|
{
|
||||||
using namespace geometry;
|
|
||||||
typedef boost::shared_ptr<Test> SharedTest;
|
typedef boost::shared_ptr<Test> SharedTest;
|
||||||
typedef boost::shared_ptr<Test> Shared;
|
typedef boost::shared_ptr<Test> Shared;
|
||||||
checkArguments("return_TestPtr",nargout,nargin-1,1);
|
checkArguments("return_TestPtr",nargout,nargin-1,1);
|
||||||
|
|
@ -371,7 +354,6 @@ using namespace geometry;
|
||||||
|
|
||||||
void Test_return_bool_28(int nargout, mxArray *out[], int nargin, const mxArray *in[])
|
void Test_return_bool_28(int nargout, mxArray *out[], int nargin, const mxArray *in[])
|
||||||
{
|
{
|
||||||
using namespace geometry;
|
|
||||||
typedef boost::shared_ptr<Test> Shared;
|
typedef boost::shared_ptr<Test> Shared;
|
||||||
checkArguments("return_bool",nargout,nargin-1,1);
|
checkArguments("return_bool",nargout,nargin-1,1);
|
||||||
Shared obj = unwrap_shared_ptr<Test>(in[0], "ptr_Test");
|
Shared obj = unwrap_shared_ptr<Test>(in[0], "ptr_Test");
|
||||||
|
|
@ -381,7 +363,6 @@ using namespace geometry;
|
||||||
|
|
||||||
void Test_return_double_29(int nargout, mxArray *out[], int nargin, const mxArray *in[])
|
void Test_return_double_29(int nargout, mxArray *out[], int nargin, const mxArray *in[])
|
||||||
{
|
{
|
||||||
using namespace geometry;
|
|
||||||
typedef boost::shared_ptr<Test> Shared;
|
typedef boost::shared_ptr<Test> Shared;
|
||||||
checkArguments("return_double",nargout,nargin-1,1);
|
checkArguments("return_double",nargout,nargin-1,1);
|
||||||
Shared obj = unwrap_shared_ptr<Test>(in[0], "ptr_Test");
|
Shared obj = unwrap_shared_ptr<Test>(in[0], "ptr_Test");
|
||||||
|
|
@ -391,7 +372,6 @@ using namespace geometry;
|
||||||
|
|
||||||
void Test_return_field_30(int nargout, mxArray *out[], int nargin, const mxArray *in[])
|
void Test_return_field_30(int nargout, mxArray *out[], int nargin, const mxArray *in[])
|
||||||
{
|
{
|
||||||
using namespace geometry;
|
|
||||||
typedef boost::shared_ptr<Test> Shared;
|
typedef boost::shared_ptr<Test> Shared;
|
||||||
checkArguments("return_field",nargout,nargin-1,1);
|
checkArguments("return_field",nargout,nargin-1,1);
|
||||||
Shared obj = unwrap_shared_ptr<Test>(in[0], "ptr_Test");
|
Shared obj = unwrap_shared_ptr<Test>(in[0], "ptr_Test");
|
||||||
|
|
@ -401,7 +381,6 @@ using namespace geometry;
|
||||||
|
|
||||||
void Test_return_int_31(int nargout, mxArray *out[], int nargin, const mxArray *in[])
|
void Test_return_int_31(int nargout, mxArray *out[], int nargin, const mxArray *in[])
|
||||||
{
|
{
|
||||||
using namespace geometry;
|
|
||||||
typedef boost::shared_ptr<Test> Shared;
|
typedef boost::shared_ptr<Test> Shared;
|
||||||
checkArguments("return_int",nargout,nargin-1,1);
|
checkArguments("return_int",nargout,nargin-1,1);
|
||||||
Shared obj = unwrap_shared_ptr<Test>(in[0], "ptr_Test");
|
Shared obj = unwrap_shared_ptr<Test>(in[0], "ptr_Test");
|
||||||
|
|
@ -411,7 +390,6 @@ using namespace geometry;
|
||||||
|
|
||||||
void Test_return_matrix1_32(int nargout, mxArray *out[], int nargin, const mxArray *in[])
|
void Test_return_matrix1_32(int nargout, mxArray *out[], int nargin, const mxArray *in[])
|
||||||
{
|
{
|
||||||
using namespace geometry;
|
|
||||||
typedef boost::shared_ptr<Test> Shared;
|
typedef boost::shared_ptr<Test> Shared;
|
||||||
checkArguments("return_matrix1",nargout,nargin-1,1);
|
checkArguments("return_matrix1",nargout,nargin-1,1);
|
||||||
Shared obj = unwrap_shared_ptr<Test>(in[0], "ptr_Test");
|
Shared obj = unwrap_shared_ptr<Test>(in[0], "ptr_Test");
|
||||||
|
|
@ -421,7 +399,6 @@ using namespace geometry;
|
||||||
|
|
||||||
void Test_return_matrix2_33(int nargout, mxArray *out[], int nargin, const mxArray *in[])
|
void Test_return_matrix2_33(int nargout, mxArray *out[], int nargin, const mxArray *in[])
|
||||||
{
|
{
|
||||||
using namespace geometry;
|
|
||||||
typedef boost::shared_ptr<Test> Shared;
|
typedef boost::shared_ptr<Test> Shared;
|
||||||
checkArguments("return_matrix2",nargout,nargin-1,1);
|
checkArguments("return_matrix2",nargout,nargin-1,1);
|
||||||
Shared obj = unwrap_shared_ptr<Test>(in[0], "ptr_Test");
|
Shared obj = unwrap_shared_ptr<Test>(in[0], "ptr_Test");
|
||||||
|
|
@ -431,7 +408,6 @@ using namespace geometry;
|
||||||
|
|
||||||
void Test_return_pair_34(int nargout, mxArray *out[], int nargin, const mxArray *in[])
|
void Test_return_pair_34(int nargout, mxArray *out[], int nargin, const mxArray *in[])
|
||||||
{
|
{
|
||||||
using namespace geometry;
|
|
||||||
typedef boost::shared_ptr<Test> Shared;
|
typedef boost::shared_ptr<Test> Shared;
|
||||||
checkArguments("return_pair",nargout,nargin-1,2);
|
checkArguments("return_pair",nargout,nargin-1,2);
|
||||||
Shared obj = unwrap_shared_ptr<Test>(in[0], "ptr_Test");
|
Shared obj = unwrap_shared_ptr<Test>(in[0], "ptr_Test");
|
||||||
|
|
@ -443,7 +419,6 @@ using namespace geometry;
|
||||||
|
|
||||||
void Test_return_ptrs_35(int nargout, mxArray *out[], int nargin, const mxArray *in[])
|
void Test_return_ptrs_35(int nargout, mxArray *out[], int nargin, const mxArray *in[])
|
||||||
{
|
{
|
||||||
using namespace geometry;
|
|
||||||
typedef boost::shared_ptr<Test> SharedTest;
|
typedef boost::shared_ptr<Test> SharedTest;
|
||||||
typedef boost::shared_ptr<Test> SharedTest;
|
typedef boost::shared_ptr<Test> SharedTest;
|
||||||
typedef boost::shared_ptr<Test> Shared;
|
typedef boost::shared_ptr<Test> Shared;
|
||||||
|
|
@ -457,7 +432,6 @@ using namespace geometry;
|
||||||
|
|
||||||
void Test_return_size_t_36(int nargout, mxArray *out[], int nargin, const mxArray *in[])
|
void Test_return_size_t_36(int nargout, mxArray *out[], int nargin, const mxArray *in[])
|
||||||
{
|
{
|
||||||
using namespace geometry;
|
|
||||||
typedef boost::shared_ptr<Test> Shared;
|
typedef boost::shared_ptr<Test> Shared;
|
||||||
checkArguments("return_size_t",nargout,nargin-1,1);
|
checkArguments("return_size_t",nargout,nargin-1,1);
|
||||||
Shared obj = unwrap_shared_ptr<Test>(in[0], "ptr_Test");
|
Shared obj = unwrap_shared_ptr<Test>(in[0], "ptr_Test");
|
||||||
|
|
@ -467,7 +441,6 @@ using namespace geometry;
|
||||||
|
|
||||||
void Test_return_string_37(int nargout, mxArray *out[], int nargin, const mxArray *in[])
|
void Test_return_string_37(int nargout, mxArray *out[], int nargin, const mxArray *in[])
|
||||||
{
|
{
|
||||||
using namespace geometry;
|
|
||||||
typedef boost::shared_ptr<Test> Shared;
|
typedef boost::shared_ptr<Test> Shared;
|
||||||
checkArguments("return_string",nargout,nargin-1,1);
|
checkArguments("return_string",nargout,nargin-1,1);
|
||||||
Shared obj = unwrap_shared_ptr<Test>(in[0], "ptr_Test");
|
Shared obj = unwrap_shared_ptr<Test>(in[0], "ptr_Test");
|
||||||
|
|
@ -477,7 +450,6 @@ using namespace geometry;
|
||||||
|
|
||||||
void Test_return_vector1_38(int nargout, mxArray *out[], int nargin, const mxArray *in[])
|
void Test_return_vector1_38(int nargout, mxArray *out[], int nargin, const mxArray *in[])
|
||||||
{
|
{
|
||||||
using namespace geometry;
|
|
||||||
typedef boost::shared_ptr<Test> Shared;
|
typedef boost::shared_ptr<Test> Shared;
|
||||||
checkArguments("return_vector1",nargout,nargin-1,1);
|
checkArguments("return_vector1",nargout,nargin-1,1);
|
||||||
Shared obj = unwrap_shared_ptr<Test>(in[0], "ptr_Test");
|
Shared obj = unwrap_shared_ptr<Test>(in[0], "ptr_Test");
|
||||||
|
|
@ -487,7 +459,6 @@ using namespace geometry;
|
||||||
|
|
||||||
void Test_return_vector2_39(int nargout, mxArray *out[], int nargin, const mxArray *in[])
|
void Test_return_vector2_39(int nargout, mxArray *out[], int nargin, const mxArray *in[])
|
||||||
{
|
{
|
||||||
using namespace geometry;
|
|
||||||
typedef boost::shared_ptr<Test> Shared;
|
typedef boost::shared_ptr<Test> Shared;
|
||||||
checkArguments("return_vector2",nargout,nargin-1,1);
|
checkArguments("return_vector2",nargout,nargin-1,1);
|
||||||
Shared obj = unwrap_shared_ptr<Test>(in[0], "ptr_Test");
|
Shared obj = unwrap_shared_ptr<Test>(in[0], "ptr_Test");
|
||||||
|
|
@ -495,6 +466,11 @@ using namespace geometry;
|
||||||
out[0] = wrap< Vector >(obj->return_vector2(value));
|
out[0] = wrap< Vector >(obj->return_vector2(value));
|
||||||
}
|
}
|
||||||
|
|
||||||
|
void aGlobalFunction_40(int nargout, mxArray *out[], int nargin, const mxArray *in[])
|
||||||
|
{
|
||||||
|
checkArguments("aGlobalFunction",nargout,nargin,0);
|
||||||
|
out[0] = wrap< Vector >(aGlobalFunction());
|
||||||
|
}
|
||||||
|
|
||||||
void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[])
|
void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[])
|
||||||
{
|
{
|
||||||
|
|
@ -626,6 +602,9 @@ void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[])
|
||||||
case 39:
|
case 39:
|
||||||
Test_return_vector2_39(nargout, out, nargin-1, in+1);
|
Test_return_vector2_39(nargout, out, nargin-1, in+1);
|
||||||
break;
|
break;
|
||||||
|
case 40:
|
||||||
|
aGlobalFunction_40(nargout, out, nargin-1, in+1);
|
||||||
|
break;
|
||||||
}
|
}
|
||||||
|
|
||||||
std::cout.rdbuf(outbuf);
|
std::cout.rdbuf(outbuf);
|
||||||
|
|
|
||||||
|
|
@ -0,0 +1,7 @@
|
||||||
|
% automatically generated by wrap
|
||||||
|
function varargout = aGlobalFunction(varargin)
|
||||||
|
if length(varargin) == 0
|
||||||
|
varargout{1} = testNamespaces_wrapper(22, varargin{:});
|
||||||
|
else
|
||||||
|
error('Arguments do not match any overload of function ns1.aGlobalFunction');
|
||||||
|
end
|
||||||
|
|
@ -0,0 +1,7 @@
|
||||||
|
% automatically generated by wrap
|
||||||
|
function varargout = aGlobalFunction(varargin)
|
||||||
|
if length(varargin) == 0
|
||||||
|
varargout{1} = testNamespaces_wrapper(23, varargin{:});
|
||||||
|
else
|
||||||
|
error('Arguments do not match any overload of function ns2.aGlobalFunction');
|
||||||
|
end
|
||||||
|
|
@ -332,6 +332,17 @@ void ClassD_deconstructor_21(int nargout, mxArray *out[], int nargin, const mxAr
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
void ns1aGlobalFunction_22(int nargout, mxArray *out[], int nargin, const mxArray *in[])
|
||||||
|
{
|
||||||
|
checkArguments("ns1aGlobalFunction",nargout,nargin,0);
|
||||||
|
out[0] = wrap< Vector >(ns1::aGlobalFunction());
|
||||||
|
}
|
||||||
|
|
||||||
|
void ns2aGlobalFunction_23(int nargout, mxArray *out[], int nargin, const mxArray *in[])
|
||||||
|
{
|
||||||
|
checkArguments("ns2aGlobalFunction",nargout,nargin,0);
|
||||||
|
out[0] = wrap< Vector >(ns2::aGlobalFunction());
|
||||||
|
}
|
||||||
|
|
||||||
void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[])
|
void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[])
|
||||||
{
|
{
|
||||||
|
|
@ -409,6 +420,12 @@ void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[])
|
||||||
case 21:
|
case 21:
|
||||||
ClassD_deconstructor_21(nargout, out, nargin-1, in+1);
|
ClassD_deconstructor_21(nargout, out, nargin-1, in+1);
|
||||||
break;
|
break;
|
||||||
|
case 22:
|
||||||
|
ns1aGlobalFunction_22(nargout, out, nargin-1, in+1);
|
||||||
|
break;
|
||||||
|
case 23:
|
||||||
|
ns2aGlobalFunction_23(nargout, out, nargin-1, in+1);
|
||||||
|
break;
|
||||||
}
|
}
|
||||||
|
|
||||||
std::cout.rdbuf(outbuf);
|
std::cout.rdbuf(outbuf);
|
||||||
|
|
|
||||||
|
|
@ -15,9 +15,6 @@ class Point2 {
|
||||||
VectorNotEigen vectorConfusion();
|
VectorNotEigen vectorConfusion();
|
||||||
};
|
};
|
||||||
|
|
||||||
// flag a namespace as in use - only applies *after* the declaration
|
|
||||||
using namespace geometry;
|
|
||||||
|
|
||||||
class Point3 {
|
class Point3 {
|
||||||
Point3(double x, double y, double z);
|
Point3(double x, double y, double z);
|
||||||
double norm() const;
|
double norm() const;
|
||||||
|
|
@ -82,6 +79,9 @@ class Test {
|
||||||
// even more comments at the end!
|
// even more comments at the end!
|
||||||
};
|
};
|
||||||
|
|
||||||
|
|
||||||
|
Vector aGlobalFunction();
|
||||||
|
|
||||||
// comments at the end!
|
// comments at the end!
|
||||||
|
|
||||||
// even more comments at the end!
|
// even more comments at the end!
|
||||||
|
|
|
||||||
|
|
@ -14,7 +14,10 @@ class ClassB {
|
||||||
ClassB();
|
ClassB();
|
||||||
};
|
};
|
||||||
|
|
||||||
}///\namespace ns1
|
// check namespace handling
|
||||||
|
Vector aGlobalFunction();
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
#include <path/to/ns2.h>
|
#include <path/to/ns2.h>
|
||||||
namespace ns2 {
|
namespace ns2 {
|
||||||
|
|
@ -35,13 +38,16 @@ class ClassB {
|
||||||
ClassB();
|
ClassB();
|
||||||
};
|
};
|
||||||
|
|
||||||
}///\namespace ns3
|
}
|
||||||
|
|
||||||
class ClassC {
|
class ClassC {
|
||||||
ClassC();
|
ClassC();
|
||||||
};
|
};
|
||||||
|
|
||||||
}///\namespace ns2
|
// separate namespace global function, same name
|
||||||
|
Vector aGlobalFunction();
|
||||||
|
|
||||||
|
} //\namespace ns2
|
||||||
|
|
||||||
class ClassD {
|
class ClassD {
|
||||||
ClassD();
|
ClassD();
|
||||||
|
|
|
||||||
|
|
@ -76,9 +76,6 @@ TEST( wrap, parse_geometry ) {
|
||||||
Module module(markup_header_path.c_str(), "geometry",enable_verbose);
|
Module module(markup_header_path.c_str(), "geometry",enable_verbose);
|
||||||
EXPECT_LONGS_EQUAL(3, module.classes.size());
|
EXPECT_LONGS_EQUAL(3, module.classes.size());
|
||||||
|
|
||||||
// check using declarations
|
|
||||||
strvec exp_using1, exp_using2; exp_using2 += "geometry";
|
|
||||||
|
|
||||||
// forward declarations
|
// forward declarations
|
||||||
LONGS_EQUAL(2, module.forward_declarations.size());
|
LONGS_EQUAL(2, module.forward_declarations.size());
|
||||||
EXPECT(assert_equal("VectorNotEigen", module.forward_declarations[0].name));
|
EXPECT(assert_equal("VectorNotEigen", module.forward_declarations[0].name));
|
||||||
|
|
@ -88,6 +85,8 @@ TEST( wrap, parse_geometry ) {
|
||||||
strvec exp_includes; exp_includes += "folder/path/to/Test.h";
|
strvec exp_includes; exp_includes += "folder/path/to/Test.h";
|
||||||
EXPECT(assert_equal(exp_includes, module.includes));
|
EXPECT(assert_equal(exp_includes, module.includes));
|
||||||
|
|
||||||
|
LONGS_EQUAL(3, module.classes.size());
|
||||||
|
|
||||||
// check first class, Point2
|
// check first class, Point2
|
||||||
{
|
{
|
||||||
Class cls = module.classes.at(0);
|
Class cls = module.classes.at(0);
|
||||||
|
|
@ -96,7 +95,6 @@ TEST( wrap, parse_geometry ) {
|
||||||
EXPECT_LONGS_EQUAL(7, cls.methods.size());
|
EXPECT_LONGS_EQUAL(7, cls.methods.size());
|
||||||
EXPECT_LONGS_EQUAL(0, cls.static_methods.size());
|
EXPECT_LONGS_EQUAL(0, cls.static_methods.size());
|
||||||
EXPECT_LONGS_EQUAL(0, cls.namespaces.size());
|
EXPECT_LONGS_EQUAL(0, cls.namespaces.size());
|
||||||
EXPECT(assert_equal(exp_using1, cls.using_namespaces));
|
|
||||||
}
|
}
|
||||||
|
|
||||||
// check second class, Point3
|
// check second class, Point3
|
||||||
|
|
@ -107,7 +105,6 @@ TEST( wrap, parse_geometry ) {
|
||||||
EXPECT_LONGS_EQUAL(1, cls.methods.size());
|
EXPECT_LONGS_EQUAL(1, cls.methods.size());
|
||||||
EXPECT_LONGS_EQUAL(2, cls.static_methods.size());
|
EXPECT_LONGS_EQUAL(2, cls.static_methods.size());
|
||||||
EXPECT_LONGS_EQUAL(0, cls.namespaces.size());
|
EXPECT_LONGS_EQUAL(0, cls.namespaces.size());
|
||||||
EXPECT(assert_equal(exp_using2, cls.using_namespaces));
|
|
||||||
|
|
||||||
// first constructor takes 3 doubles
|
// first constructor takes 3 doubles
|
||||||
ArgumentList c1 = cls.constructor.args_list.front();
|
ArgumentList c1 = cls.constructor.args_list.front();
|
||||||
|
|
@ -133,13 +130,11 @@ TEST( wrap, parse_geometry ) {
|
||||||
|
|
||||||
// Test class is the third one
|
// Test class is the third one
|
||||||
{
|
{
|
||||||
LONGS_EQUAL(3, module.classes.size());
|
|
||||||
Class testCls = module.classes.at(2);
|
Class testCls = module.classes.at(2);
|
||||||
EXPECT_LONGS_EQUAL( 2, testCls.constructor.args_list.size());
|
EXPECT_LONGS_EQUAL( 2, testCls.constructor.args_list.size());
|
||||||
EXPECT_LONGS_EQUAL(19, testCls.methods.size());
|
EXPECT_LONGS_EQUAL(19, testCls.methods.size());
|
||||||
EXPECT_LONGS_EQUAL( 0, testCls.static_methods.size());
|
EXPECT_LONGS_EQUAL( 0, testCls.static_methods.size());
|
||||||
EXPECT_LONGS_EQUAL( 0, testCls.namespaces.size());
|
EXPECT_LONGS_EQUAL( 0, testCls.namespaces.size());
|
||||||
EXPECT(assert_equal(exp_using2, testCls.using_namespaces));
|
|
||||||
|
|
||||||
// function to parse: pair<Vector,Matrix> return_pair (Vector v, Matrix A) const;
|
// function to parse: pair<Vector,Matrix> return_pair (Vector v, Matrix A) const;
|
||||||
CHECK(testCls.methods.find("return_pair") != testCls.methods.end());
|
CHECK(testCls.methods.find("return_pair") != testCls.methods.end());
|
||||||
|
|
@ -149,6 +144,20 @@ TEST( wrap, parse_geometry ) {
|
||||||
EXPECT(m2.returnVals.front().category1 == ReturnValue::EIGEN);
|
EXPECT(m2.returnVals.front().category1 == ReturnValue::EIGEN);
|
||||||
EXPECT(m2.returnVals.front().category2 == ReturnValue::EIGEN);
|
EXPECT(m2.returnVals.front().category2 == ReturnValue::EIGEN);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// evaluate global functions
|
||||||
|
// Vector aGlobalFunction();
|
||||||
|
LONGS_EQUAL(1, module.global_functions.size());
|
||||||
|
CHECK(module.global_functions.find("aGlobalFunction") != module.global_functions.end());
|
||||||
|
{
|
||||||
|
GlobalFunction gfunc = module.global_functions.at("aGlobalFunction");
|
||||||
|
EXPECT(assert_equal("aGlobalFunction", gfunc.name));
|
||||||
|
LONGS_EQUAL(1, gfunc.returnVals.size());
|
||||||
|
EXPECT(assert_equal("Vector", gfunc.returnVals.front().type1));
|
||||||
|
EXPECT_LONGS_EQUAL(1, gfunc.argLists.size());
|
||||||
|
LONGS_EQUAL(1, gfunc.namespaces.size());
|
||||||
|
EXPECT(gfunc.namespaces.front().empty());
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
/* ************************************************************************* */
|
/* ************************************************************************* */
|
||||||
|
|
@ -208,6 +217,27 @@ TEST( wrap, parse_namespaces ) {
|
||||||
strvec exp_namespaces;
|
strvec exp_namespaces;
|
||||||
EXPECT(assert_equal(exp_namespaces, cls.namespaces));
|
EXPECT(assert_equal(exp_namespaces, cls.namespaces));
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// evaluate global functions
|
||||||
|
// Vector ns1::aGlobalFunction();
|
||||||
|
// Vector ns2::aGlobalFunction();
|
||||||
|
LONGS_EQUAL(1, module.global_functions.size());
|
||||||
|
CHECK(module.global_functions.find("aGlobalFunction") != module.global_functions.end());
|
||||||
|
{
|
||||||
|
GlobalFunction gfunc = module.global_functions.at("aGlobalFunction");
|
||||||
|
EXPECT(assert_equal("aGlobalFunction", gfunc.name));
|
||||||
|
LONGS_EQUAL(2, gfunc.returnVals.size());
|
||||||
|
EXPECT(assert_equal("Vector", gfunc.returnVals.front().type1));
|
||||||
|
EXPECT_LONGS_EQUAL(2, gfunc.argLists.size());
|
||||||
|
|
||||||
|
// check namespaces
|
||||||
|
LONGS_EQUAL(2, gfunc.namespaces.size());
|
||||||
|
strvec exp_namespaces1; exp_namespaces1 += "ns1";
|
||||||
|
EXPECT(assert_equal(exp_namespaces1, gfunc.namespaces.at(0)));
|
||||||
|
|
||||||
|
strvec exp_namespaces2; exp_namespaces2 += "ns2";
|
||||||
|
EXPECT(assert_equal(exp_namespaces2, gfunc.namespaces.at(1)));
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
/* ************************************************************************* */
|
/* ************************************************************************* */
|
||||||
|
|
@ -255,6 +285,7 @@ TEST( wrap, matlab_code_geometry ) {
|
||||||
EXPECT(files_equal(epath + "Point2.m" , apath + "Point2.m" ));
|
EXPECT(files_equal(epath + "Point2.m" , apath + "Point2.m" ));
|
||||||
EXPECT(files_equal(epath + "Point3.m" , apath + "Point3.m" ));
|
EXPECT(files_equal(epath + "Point3.m" , apath + "Point3.m" ));
|
||||||
EXPECT(files_equal(epath + "Test.m" , apath + "Test.m" ));
|
EXPECT(files_equal(epath + "Test.m" , apath + "Test.m" ));
|
||||||
|
EXPECT(files_equal(epath + "aGlobalFunction.m" , apath + "aGlobalFunction.m" ));
|
||||||
}
|
}
|
||||||
|
|
||||||
/* ************************************************************************* */
|
/* ************************************************************************* */
|
||||||
|
|
|
||||||
|
|
@ -20,6 +20,7 @@
|
||||||
#include <cstdlib>
|
#include <cstdlib>
|
||||||
|
|
||||||
#include <boost/foreach.hpp>
|
#include <boost/foreach.hpp>
|
||||||
|
#include <boost/filesystem.hpp>
|
||||||
|
|
||||||
#include "utilities.h"
|
#include "utilities.h"
|
||||||
|
|
||||||
|
|
@ -114,13 +115,6 @@ string maybe_shared_ptr(bool add, const string& qtype, const string& type) {
|
||||||
return str;
|
return str;
|
||||||
}
|
}
|
||||||
|
|
||||||
/* ************************************************************************* */
|
|
||||||
void generateUsingNamespace(FileWriter& file, const vector<string>& using_namespaces) {
|
|
||||||
if (using_namespaces.empty()) return;
|
|
||||||
BOOST_FOREACH(const string& s, using_namespaces)
|
|
||||||
file.oss << "using namespace " << s << ";" << endl;
|
|
||||||
}
|
|
||||||
|
|
||||||
/* ************************************************************************* */
|
/* ************************************************************************* */
|
||||||
string qualifiedName(const string& separator, const vector<string>& names, const string& finalName) {
|
string qualifiedName(const string& separator, const vector<string>& names, const string& finalName) {
|
||||||
string result;
|
string result;
|
||||||
|
|
@ -137,6 +131,21 @@ string qualifiedName(const string& separator, const vector<string>& names, const
|
||||||
return result;
|
return result;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
/* ************************************************************************* */
|
||||||
|
void createNamespaceStructure(const std::vector<std::string>& namespaces, const std::string& toolboxPath) {
|
||||||
|
using namespace boost::filesystem;
|
||||||
|
path curPath = toolboxPath;
|
||||||
|
BOOST_FOREACH(const string& subdir, namespaces) {
|
||||||
|
curPath /= "+" + subdir;
|
||||||
|
if(!is_directory(curPath)) {
|
||||||
|
if(exists("+" + subdir))
|
||||||
|
throw OutputError("Need to write files to directory " + curPath.string() + ", which already exists as a file but is not a directory");
|
||||||
|
else
|
||||||
|
boost::filesystem::create_directory(curPath);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
/* ************************************************************************* */
|
/* ************************************************************************* */
|
||||||
|
|
||||||
} // \namespace wrap
|
} // \namespace wrap
|
||||||
|
|
|
||||||
|
|
@ -122,15 +122,13 @@ bool assert_equal(const std::vector<std::string>& expected, const std::vector<st
|
||||||
// auxiliary function to wrap an argument into a shared_ptr template
|
// auxiliary function to wrap an argument into a shared_ptr template
|
||||||
std::string maybe_shared_ptr(bool add, const std::string& qtype, const std::string& type);
|
std::string maybe_shared_ptr(bool add, const std::string& qtype, const std::string& type);
|
||||||
|
|
||||||
/**
|
|
||||||
* Creates the "using namespace [name];" declarations
|
|
||||||
*/
|
|
||||||
void generateUsingNamespace(FileWriter& file, const std::vector<std::string>& using_namespaces);
|
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Return a qualified name, if finalName is empty, only the names vector will
|
* Return a qualified name, if finalName is empty, only the names vector will
|
||||||
* be used (i.e. there won't be a trailing separator on the qualified name).
|
* be used (i.e. there won't be a trailing separator on the qualified name).
|
||||||
*/
|
*/
|
||||||
std::string qualifiedName(const std::string& separator, const std::vector<std::string>& names, const std::string& finalName = "");
|
std::string qualifiedName(const std::string& separator, const std::vector<std::string>& names, const std::string& finalName = "");
|
||||||
|
|
||||||
|
/** creates the necessary folders for namespaces, as specified by a namespace stack */
|
||||||
|
void createNamespaceStructure(const std::vector<std::string>& namespaces, const std::string& toolboxPath);
|
||||||
|
|
||||||
} // \namespace wrap
|
} // \namespace wrap
|
||||||
|
|
|
||||||
Loading…
Reference in New Issue