Merge remote-tracking branch 'svn/branches/wrap_mods' into wrap_mods_inheritance

Conflicts:
	gtsam.h
release/4.3a0
Richard Roberts 2012-07-09 20:27:23 +00:00
commit 4a0866b519
140 changed files with 1828 additions and 1772 deletions

28
gtsam.h
View File

@ -6,25 +6,27 @@
*
* Requirements:
* Classes must start with an uppercase letter
* Only one Method/Constructor per line
* - Can wrap a typedef
* Only one Method/Constructor per line, though methods/constructors can extend across multiple lines
* Methods can return
* - Eigen types: Matrix, Vector
* - C/C++ basic types: string, bool, size_t, size_t, double, char, unsigned char
* - void
* - Any class with which be copied with boost::make_shared()
* - boost::shared_ptr of any object type
* Constructors
<* Constructors
* - Overloads are supported
* - A class with no constructors can be returned from other functions but not allocated directly in MATLAB
* Methods
* - Constness has no effect
* - Specify by-value (not reference) return types, even if C++ method returns reference
* - Must start with a lowercase letter
* - Overloads are supported
* Static methods
* - Must start with a letter (upper or lowercase) and use the "static" keyword
* - Static method names will be changed to start with an uppercase letter in the generated MATLAB interface
* - The first letter will be made uppercase in the generated MATLAB interface
* - Overloads are supported
* Arguments to functions any of
=* Arguments to functions any of
* - Eigen types: Matrix, Vector
* - Eigen types and classes as an optionally const reference
* - C/C++ basic types: string, bool, size_t, size_t, double, char, unsigned char
@ -40,7 +42,7 @@
* Namespace usage
* - 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"
* Using namespace
* 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
@ -931,8 +933,20 @@ class Ordering {
void insert(size_t key, size_t order);
void push_back(size_t key);
void permuteWithInverse(const gtsam::Permutation& inversePermutation);
// FIXME: Wrap InvertedMap as well
//InvertedMap invert() const;
gtsam::InvertedOrdering invert() const;
};
#include <gtsam/nonlinear/Ordering.h>
class InvertedOrdering {
InvertedOrdering();
// FIXME: add bracket operator overload
bool empty() const;
size_t size() const;
bool count(size_t index) const; // Use as a boolean function with implicit cast
void clear();
};
class NonlinearFactorGraph {

View File

@ -233,7 +233,10 @@ private:
ar & BOOST_SERIALIZATION_NVP(order_);
ar & BOOST_SERIALIZATION_NVP(nVars_);
}
};
}; // \class Ordering
// typedef for use with matlab
typedef Ordering::InvertedMap InvertedOrdering;
/**
* @class Unordered

View File

@ -29,7 +29,7 @@ data.K = truth.K;
for i=1:options.nrCameras
theta = (i-1)*2*pi/options.nrCameras;
t = gtsamPoint3([r*cos(theta), r*sin(theta), height]');
truth.cameras{i} = gtsamSimpleCamera_lookat(t, gtsamPoint3, gtsamPoint3([0,0,1]'), truth.K);
truth.cameras{i} = gtsamSimpleCamera.Lookat(t, gtsamPoint3, gtsamPoint3([0,0,1]'), truth.K);
% Create measurements
for j=1:nrPoints
% All landmarks seen in every frame

View File

@ -6,10 +6,10 @@ function [noiseModels,isam,result] = VisualISAMInitialize(data,truth,options)
isam = visualSLAMISAM(options.reorderInterval);
%% Set Noise parameters
noiseModels.pose = gtsamnoiseModelDiagonal_Sigmas([0.001 0.001 0.001 0.1 0.1 0.1]');
noiseModels.odometry = gtsamnoiseModelDiagonal_Sigmas([0.001 0.001 0.001 0.1 0.1 0.1]');
noiseModels.point = gtsamnoiseModelIsotropic_Sigma(3, 0.1);
noiseModels.measurement = gtsamnoiseModelIsotropic_Sigma(2, 1.0);
noiseModels.pose = gtsamnoiseModelDiagonal.Sigmas([0.001 0.001 0.001 0.1 0.1 0.1]');
noiseModels.odometry = gtsamnoiseModelDiagonal.Sigmas([0.001 0.001 0.001 0.1 0.1 0.1]');
noiseModels.point = gtsamnoiseModelIsotropic.Sigma(3, 0.1);
noiseModels.measurement = gtsamnoiseModelIsotropic.Sigma(2, 1.0);
%% Add constraints/priors
% TODO: should not be from ground truth!

View File

@ -20,13 +20,13 @@ graph = pose2SLAMGraph;
%% Add two odometry factors
odometry = gtsamPose2(2.0, 0.0, 0.0); % create a measurement for both factors (the same in this case)
odometryNoise = gtsamnoiseModelDiagonal_Sigmas([0.2; 0.2; 0.1]); % 20cm std on x,y, 0.1 rad on theta
odometryNoise = gtsamnoiseModelDiagonal.Sigmas([0.2; 0.2; 0.1]); % 20cm std on x,y, 0.1 rad on theta
graph.addRelativePose(1, 2, odometry, odometryNoise);
graph.addRelativePose(2, 3, odometry, odometryNoise);
%% Add three "GPS" measurements
% We use Pose2 Priors here with high variance on theta
noiseModel = gtsamnoiseModelDiagonal_Sigmas([0.1; 0.1; 10]);
noiseModel = gtsamnoiseModelDiagonal.Sigmas([0.1; 0.1; 10]);
graph.addPosePrior(1, gtsamPose2(0.0, 0.0, 0.0), noiseModel);
graph.addPosePrior(2, gtsamPose2(2.0, 0.0, 0.0), noiseModel);
graph.addPosePrior(3, gtsamPose2(4.0, 0.0, 0.0), noiseModel);

View File

@ -20,12 +20,12 @@ graph = pose2SLAMGraph;
%% Add a Gaussian prior on pose x_1
priorMean = gtsamPose2(0.0, 0.0, 0.0); % prior mean is at origin
priorNoise = gtsamnoiseModelDiagonal_Sigmas([0.3; 0.3; 0.1]); % 30cm std on x,y, 0.1 rad on theta
priorNoise = gtsamnoiseModelDiagonal.Sigmas([0.3; 0.3; 0.1]); % 30cm std on x,y, 0.1 rad on theta
graph.addPosePrior(1, priorMean, priorNoise); % add directly to graph
%% Add two odometry factors
odometry = gtsamPose2(2.0, 0.0, 0.0); % create a measurement for both factors (the same in this case)
odometryNoise = gtsamnoiseModelDiagonal_Sigmas([0.2; 0.2; 0.1]); % 20cm std on x,y, 0.1 rad on theta
odometryNoise = gtsamnoiseModelDiagonal.Sigmas([0.2; 0.2; 0.1]); % 20cm std on x,y, 0.1 rad on theta
graph.addRelativePose(1, 2, odometry, odometryNoise);
graph.addRelativePose(2, 3, odometry, odometryNoise);

View File

@ -28,18 +28,18 @@ graph = planarSLAMGraph;
%% Add prior
priorMean = gtsamPose2(0.0, 0.0, 0.0); % prior at origin
priorNoise = gtsamnoiseModelDiagonal_Sigmas([0.3; 0.3; 0.1]);
priorNoise = gtsamnoiseModelDiagonal.Sigmas([0.3; 0.3; 0.1]);
graph.addPosePrior(i1, priorMean, priorNoise); % add directly to graph
%% Add odometry
odometry = gtsamPose2(2.0, 0.0, 0.0);
odometryNoise = gtsamnoiseModelDiagonal_Sigmas([0.2; 0.2; 0.1]);
odometryNoise = gtsamnoiseModelDiagonal.Sigmas([0.2; 0.2; 0.1]);
graph.addRelativePose(i1, i2, odometry, odometryNoise);
graph.addRelativePose(i2, i3, odometry, odometryNoise);
%% Add bearing/range measurement factors
degrees = pi/180;
noiseModel = gtsamnoiseModelDiagonal_Sigmas([0.1; 0.2]);
noiseModel = gtsamnoiseModelDiagonal.Sigmas([0.1; 0.2]);
graph.addBearingRange(i1, j1, gtsamRot2(45*degrees), sqrt(4+4), noiseModel);
graph.addBearingRange(i2, j1, gtsamRot2(90*degrees), 2, noiseModel);
graph.addBearingRange(i3, j2, gtsamRot2(90*degrees), 2, noiseModel);

View File

@ -15,22 +15,22 @@
i1 = symbol('x',1); i2 = symbol('x',2); i3 = symbol('x',3);
graph = planarSLAMGraph;
priorMean = gtsamPose2(0.0, 0.0, 0.0); % prior at origin
priorNoise = gtsamnoiseModelDiagonal_Sigmas([0.3; 0.3; 0.1]);
priorNoise = gtsamnoiseModelDiagonal.Sigmas([0.3; 0.3; 0.1]);
graph.addPosePrior(i1, priorMean, priorNoise); % add directly to graph
odometry = gtsamPose2(2.0, 0.0, 0.0);
odometryNoise = gtsamnoiseModelDiagonal_Sigmas([0.2; 0.2; 0.1]);
odometryNoise = gtsamnoiseModelDiagonal.Sigmas([0.2; 0.2; 0.1]);
graph.addRelativePose(i1, i2, odometry, odometryNoise);
graph.addRelativePose(i2, i3, odometry, odometryNoise);
%% Except, for measurements we offer a choice
j1 = symbol('l',1); j2 = symbol('l',2);
degrees = pi/180;
noiseModel = gtsamnoiseModelDiagonal_Sigmas([0.1; 0.2]);
noiseModel = gtsamnoiseModelDiagonal.Sigmas([0.1; 0.2]);
if 1
graph.addBearingRange(i1, j1, gtsamRot2(45*degrees), sqrt(4+4), noiseModel);
graph.addBearingRange(i2, j1, gtsamRot2(90*degrees), 2, noiseModel);
else
bearingModel = gtsamnoiseModelDiagonal_Sigmas(0.1);
bearingModel = gtsamnoiseModelDiagonal.Sigmas(0.1);
graph.addBearing(i1, j1, gtsamRot2(45*degrees), bearingModel);
graph.addBearing(i2, j1, gtsamRot2(90*degrees), bearingModel);
end

View File

@ -24,19 +24,19 @@ graph = pose2SLAMGraph;
%% Add prior
% gaussian for prior
priorMean = gtsamPose2(0.0, 0.0, 0.0); % prior at origin
priorNoise = gtsamnoiseModelDiagonal_Sigmas([0.3; 0.3; 0.1]);
priorNoise = gtsamnoiseModelDiagonal.Sigmas([0.3; 0.3; 0.1]);
graph.addPosePrior(1, priorMean, priorNoise); % add directly to graph
%% Add odometry
% general noisemodel for odometry
odometryNoise = gtsamnoiseModelDiagonal_Sigmas([0.2; 0.2; 0.1]);
odometryNoise = gtsamnoiseModelDiagonal.Sigmas([0.2; 0.2; 0.1]);
graph.addRelativePose(1, 2, gtsamPose2(2.0, 0.0, 0.0 ), odometryNoise);
graph.addRelativePose(2, 3, gtsamPose2(2.0, 0.0, pi/2), odometryNoise);
graph.addRelativePose(3, 4, gtsamPose2(2.0, 0.0, pi/2), odometryNoise);
graph.addRelativePose(4, 5, gtsamPose2(2.0, 0.0, pi/2), odometryNoise);
%% Add pose constraint
model = gtsamnoiseModelDiagonal_Sigmas([0.2; 0.2; 0.1]);
model = gtsamnoiseModelDiagonal.Sigmas([0.2; 0.2; 0.1]);
graph.addRelativePose(5, 2, gtsamPose2(2.0, 0.0, pi/2), model);
% print

View File

@ -25,20 +25,20 @@ graph = pose2SLAMGraph;
%% Add prior
% gaussian for prior
priorNoise = gtsamnoiseModelDiagonal_Sigmas([0.3; 0.3; 0.1]);
priorNoise = gtsamnoiseModelDiagonal.Sigmas([0.3; 0.3; 0.1]);
priorMean = gtsamPose2(0.0, 0.0, 0.0); % prior at origin
graph.addPosePrior(1, priorMean, priorNoise); % add directly to graph
%% Add odometry
% general noisemodel for odometry
odometryNoise = gtsamnoiseModelDiagonal_Sigmas([0.2; 0.2; 0.1]);
odometryNoise = gtsamnoiseModelDiagonal.Sigmas([0.2; 0.2; 0.1]);
odometry = gtsamPose2(2.0, 0.0, 0.0); % create a measurement for both factors (the same in this case)
graph.addRelativePose(1, 2, odometry, odometryNoise);
graph.addRelativePose(2, 3, odometry, odometryNoise);
%% Add measurements
% general noisemodel for measurements
measurementNoise = gtsamnoiseModelDiagonal_Sigmas([0.1; 0.2]);
measurementNoise = gtsamnoiseModelDiagonal.Sigmas([0.1; 0.2]);
% print
graph.print('full graph');

View File

@ -11,7 +11,7 @@
%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
%% Create a hexagon of poses
hexagon = pose2SLAMValues_Circle(6,1.0);
hexagon = pose2SLAMValues.Circle(6,1.0);
p0 = hexagon.pose(0);
p1 = hexagon.pose(1);
@ -19,7 +19,7 @@ p1 = hexagon.pose(1);
fg = pose2SLAMGraph;
fg.addPoseConstraint(0, p0);
delta = p0.between(p1);
covariance = gtsamnoiseModelDiagonal_Sigmas([0.05; 0.05; 5*pi/180]);
covariance = gtsamnoiseModelDiagonal.Sigmas([0.05; 0.05; 5*pi/180]);
fg.addRelativePose(0,1, delta, covariance);
fg.addRelativePose(1,2, delta, covariance);
fg.addRelativePose(2,3, delta, covariance);

View File

@ -11,13 +11,13 @@
%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
%% Initialize graph, initial estimate, and odometry noise
model = gtsamnoiseModelDiagonal_Sigmas([0.05; 0.05; 5*pi/180]);
model = gtsamnoiseModelDiagonal.Sigmas([0.05; 0.05; 5*pi/180]);
[graph,initial]=load2D('../../examples/Data/w100-odom.graph',model);
initial.print(sprintf('Initial estimate:\n'));
%% Add a Gaussian prior on pose x_1
priorMean = gtsamPose2(0.0, 0.0, 0.0); % prior mean is at origin
priorNoise = gtsamnoiseModelDiagonal_Sigmas([0.01; 0.01; 0.01]);
priorNoise = gtsamnoiseModelDiagonal.Sigmas([0.01; 0.01; 0.01]);
graph.addPosePrior(0, priorMean, priorNoise); % add directly to graph
%% Plot Initial Estimate

View File

@ -22,19 +22,19 @@ graph = pose2SLAMGraph;
%% Add prior
% gaussian for prior
priorMean = gtsamPose2(0.0, 0.0, 0.0); % prior at origin
priorNoise = gtsamnoiseModelDiagonal_Sigmas([0.3; 0.3; 0.1]);
priorNoise = gtsamnoiseModelDiagonal.Sigmas([0.3; 0.3; 0.1]);
graph.addPrior(1, priorMean, priorNoise); % add directly to graph
%% Add odometry
% general noisemodel for odometry
odometryNoise = gtsamnoiseModelDiagonal_Sigmas([0.2; 0.2; 0.1]);
odometryNoise = gtsamnoiseModelDiagonal.Sigmas([0.2; 0.2; 0.1]);
graph.addOdometry(1, 2, gtsamPose2(2.0, 0.0, 0.0 ), odometryNoise);
graph.addOdometry(2, 3, gtsamPose2(2.0, 0.0, pi/2), odometryNoise);
graph.addOdometry(3, 4, gtsamPose2(2.0, 0.0, pi/2), odometryNoise);
graph.addOdometry(4, 5, gtsamPose2(2.0, 0.0, pi/2), odometryNoise);
%% Add pose constraint
model = gtsamnoiseModelDiagonal_Sigmas([0.2; 0.2; 0.1]);
model = gtsamnoiseModelDiagonal.Sigmas([0.2; 0.2; 0.1]);
graph.addRelativePose(5, 2, gtsamPose2(2.0, 0.0, pi/2), model);
% print

View File

@ -11,7 +11,7 @@
%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
%% Create a hexagon of poses
hexagon = pose3SLAMValues_Circle(6,1.0);
hexagon = pose3SLAMValues.Circle(6,1.0);
p0 = hexagon.pose(0);
p1 = hexagon.pose(1);
@ -19,7 +19,7 @@ p1 = hexagon.pose(1);
fg = pose3SLAMGraph;
fg.addPoseConstraint(0, p0);
delta = p0.between(p1);
covariance = gtsamnoiseModelDiagonal_Sigmas([0.05; 0.05; 0.05; 5*pi/180; 5*pi/180; 5*pi/180]);
covariance = gtsamnoiseModelDiagonal.Sigmas([0.05; 0.05; 0.05; 5*pi/180; 5*pi/180; 5*pi/180]);
fg.addRelativePose(0,1, delta, covariance);
fg.addRelativePose(1,2, delta, covariance);
fg.addRelativePose(2,3, delta, covariance);

View File

@ -16,7 +16,7 @@ N = 2500;
filename = '../../examples/Data/sphere2500.txt';
%% Initialize graph, initial estimate, and odometry noise
model = gtsamnoiseModelDiagonal_Sigmas([0.05; 0.05; 0.05; 5*pi/180; 5*pi/180; 5*pi/180]);
model = gtsamnoiseModelDiagonal.Sigmas([0.05; 0.05; 0.05; 5*pi/180; 5*pi/180; 5*pi/180]);
[graph,initial]=load3D(filename,model,true,N);
%% Plot Initial Estimate

View File

@ -34,7 +34,7 @@ graph = sparseBAGraph;
%% Add factors for all measurements
measurementNoise = gtsamnoiseModelIsotropic_Sigma(2,measurementNoiseSigma);
measurementNoise = gtsamnoiseModelIsotropic.Sigma(2,measurementNoiseSigma);
for i=1:length(data.Z)
for k=1:length(data.Z{i})
j = data.J{i}{k};
@ -43,11 +43,11 @@ for i=1:length(data.Z)
end
%% Add Gaussian priors for a pose and a landmark to constrain the system
cameraPriorNoise = gtsamnoiseModelDiagonal_Sigmas(cameraNoiseSigmas);
cameraPriorNoise = gtsamnoiseModelDiagonal.Sigmas(cameraNoiseSigmas);
firstCamera = gtsamSimpleCamera(truth.cameras{1}.pose, truth.K);
graph.addSimpleCameraPrior(symbol('c',1), firstCamera, cameraPriorNoise);
pointPriorNoise = gtsamnoiseModelIsotropic_Sigma(3,pointNoiseSigma);
pointPriorNoise = gtsamnoiseModelIsotropic.Sigma(3,pointNoiseSigma);
graph.addPointPrior(symbol('p',1), truth.points{1}, pointPriorNoise);
%% Print the graph

View File

@ -32,7 +32,7 @@ poseNoiseSigmas = [0.001 0.001 0.001 0.1 0.1 0.1]';
graph = visualSLAMGraph;
%% Add factors for all measurements
measurementNoise = gtsamnoiseModelIsotropic_Sigma(2,measurementNoiseSigma);
measurementNoise = gtsamnoiseModelIsotropic.Sigma(2,measurementNoiseSigma);
for i=1:length(data.Z)
for k=1:length(data.Z{i})
j = data.J{i}{k};
@ -41,9 +41,9 @@ for i=1:length(data.Z)
end
%% Add Gaussian priors for a pose and a landmark to constrain the system
posePriorNoise = gtsamnoiseModelDiagonal_Sigmas(poseNoiseSigmas);
posePriorNoise = gtsamnoiseModelDiagonal.Sigmas(poseNoiseSigmas);
graph.addPosePrior(symbol('x',1), truth.cameras{1}.pose, posePriorNoise);
pointPriorNoise = gtsamnoiseModelIsotropic_Sigma(3,pointNoiseSigma);
pointPriorNoise = gtsamnoiseModelIsotropic.Sigma(3,pointNoiseSigma);
graph.addPointPrior(symbol('p',1), truth.points{1}, pointPriorNoise);
%% Print the graph

View File

@ -31,7 +31,7 @@ graph.addPoseConstraint(x1, first_pose);
%% Create realistic calibration and measurement noise model
% format: fx fy skew cx cy baseline
K = gtsamCal3_S2Stereo(1000, 1000, 0, 320, 240, 0.2);
stereo_model = gtsamnoiseModelDiagonal_Sigmas([1.0; 1.0; 1.0]);
stereo_model = gtsamnoiseModelDiagonal.Sigmas([1.0; 1.0; 1.0]);
%% Add measurements
% pose 1

View File

@ -14,7 +14,7 @@
% format: fx fy skew cx cy baseline
calib = dlmread('../../examples/Data/VO_calibration.txt');
K = gtsamCal3_S2Stereo(calib(1), calib(2), calib(3), calib(4), calib(5), calib(6));
stereo_model = gtsamnoiseModelDiagonal_Sigmas([1.0; 1.0; 1.0]);
stereo_model = gtsamnoiseModelDiagonal.Sigmas([1.0; 1.0; 1.0]);
%% create empty graph and values
graph = visualSLAMGraph;

View File

@ -29,7 +29,7 @@ for i=1:n
i=v{2};
if (~successive & i<N | successive & i==0)
t = gtsamPoint3(v{3}, v{4}, v{5});
R = gtsamRot3_ypr(v{8}, -v{7}, v{6});
R = gtsamRot3.Ypr(v{8}, -v{7}, v{6});
initial.insertPose(i, gtsamPose3(R,t));
end
elseif strcmp('EDGE3',line_i(1:5))
@ -39,7 +39,7 @@ for i=1:n
if i1<N & i2<N
if ~successive | abs(i2-i1)==1
t = gtsamPoint3(e{4}, e{5}, e{6});
R = gtsamRot3_ypr(e{9}, e{8}, e{7});
R = gtsamRot3.Ypr(e{9}, e{8}, e{7});
dpose = gtsamPose3(R,t);
graph.addRelativePose(i1, i2, dpose, model);
if successive

View File

@ -30,7 +30,7 @@ x1 = 3;
% the RHS
b2=[-1;1.5;2;-1];
sigmas = [1;1;1;1];
model4 = gtsamnoiseModelDiagonal_Sigmas(sigmas);
model4 = gtsamnoiseModelDiagonal.Sigmas(sigmas);
combined = gtsamJacobianFactor(x2, Ax2, l1, Al1, x1, Ax1, b2, model4);
% eliminate the first variable (x2) in the combined factor, destructive !
@ -69,7 +69,7 @@ Bx1 = [
% the RHS
b1= [0.0;0.894427];
model2 = gtsamnoiseModelDiagonal_Sigmas([1;1]);
model2 = gtsamnoiseModelDiagonal.Sigmas([1;1]);
expectedLF = gtsamJacobianFactor(l1, Bl1, x1, Bx1, b1, model2);
% check if the result matches the combined (reduced) factor

View File

@ -22,13 +22,13 @@
F = eye(2,2);
B = eye(2,2);
u = [1.0; 0.0];
modelQ = gtsamnoiseModelDiagonal_Sigmas([0.1;0.1]);
modelQ = gtsamnoiseModelDiagonal.Sigmas([0.1;0.1]);
Q = 0.01*eye(2,2);
H = eye(2,2);
z1 = [1.0, 0.0]';
z2 = [2.0, 0.0]';
z3 = [3.0, 0.0]';
modelR = gtsamnoiseModelDiagonal_Sigmas([0.1;0.1]);
modelR = gtsamnoiseModelDiagonal.Sigmas([0.1;0.1]);
R = 0.01*eye(2,2);
%% Create the set of expected output TestValues

View File

@ -15,7 +15,7 @@ graph = pose2SLAMGraph;
%% Add two odometry factors
odometry = gtsamPose2(2.0, 0.0, 0.0); % create a measurement for both factors (the same in this case)
odometryNoise = gtsamnoiseModelDiagonal_Sigmas([0.2; 0.2; 0.1]); % 20cm std on x,y, 0.1 rad on theta
odometryNoise = gtsamnoiseModelDiagonal.Sigmas([0.2; 0.2; 0.1]); % 20cm std on x,y, 0.1 rad on theta
graph.addRelativePose(1, 2, odometry, odometryNoise);
graph.addRelativePose(2, 3, odometry, odometryNoise);
@ -25,7 +25,7 @@ groundTruth = pose2SLAMValues;
groundTruth.insertPose(1, gtsamPose2(0.0, 0.0, 0.0));
groundTruth.insertPose(2, gtsamPose2(2.0, 0.0, 0.0));
groundTruth.insertPose(3, gtsamPose2(4.0, 0.0, 0.0));
noiseModel = gtsamnoiseModelDiagonal_Sigmas([0.1; 0.1; 10]);
noiseModel = gtsamnoiseModelDiagonal.Sigmas([0.1; 0.1; 10]);
for i=1:3
graph.addPosePrior(i, groundTruth.pose(i), noiseModel);
end

View File

@ -15,12 +15,12 @@ graph = pose2SLAMGraph;
%% Add a Gaussian prior on pose x_1
priorMean = gtsamPose2(0.0, 0.0, 0.0); % prior mean is at origin
priorNoise = gtsamnoiseModelDiagonal_Sigmas([0.3; 0.3; 0.1]); % 30cm std on x,y, 0.1 rad on theta
priorNoise = gtsamnoiseModelDiagonal.Sigmas([0.3; 0.3; 0.1]); % 30cm std on x,y, 0.1 rad on theta
graph.addPosePrior(1, priorMean, priorNoise); % add directly to graph
%% Add two odometry factors
odometry = gtsamPose2(2.0, 0.0, 0.0); % create a measurement for both factors (the same in this case)
odometryNoise = gtsamnoiseModelDiagonal_Sigmas([0.2; 0.2; 0.1]); % 20cm std on x,y, 0.1 rad on theta
odometryNoise = gtsamnoiseModelDiagonal.Sigmas([0.2; 0.2; 0.1]); % 20cm std on x,y, 0.1 rad on theta
graph.addRelativePose(1, 2, odometry, odometryNoise);
graph.addRelativePose(2, 3, odometry, odometryNoise);

View File

@ -28,18 +28,18 @@ graph = planarSLAMGraph;
%% Add prior
priorMean = gtsamPose2(0.0, 0.0, 0.0); % prior at origin
priorNoise = gtsamnoiseModelDiagonal_Sigmas([0.3; 0.3; 0.1]);
priorNoise = gtsamnoiseModelDiagonal.Sigmas([0.3; 0.3; 0.1]);
graph.addPosePrior(i1, priorMean, priorNoise); % add directly to graph
%% Add odometry
odometry = gtsamPose2(2.0, 0.0, 0.0);
odometryNoise = gtsamnoiseModelDiagonal_Sigmas([0.2; 0.2; 0.1]);
odometryNoise = gtsamnoiseModelDiagonal.Sigmas([0.2; 0.2; 0.1]);
graph.addRelativePose(i1, i2, odometry, odometryNoise);
graph.addRelativePose(i2, i3, odometry, odometryNoise);
%% Add bearing/range measurement factors
degrees = pi/180;
noiseModel = gtsamnoiseModelDiagonal_Sigmas([0.1; 0.2]);
noiseModel = gtsamnoiseModelDiagonal.Sigmas([0.1; 0.2]);
graph.addBearingRange(i1, j1, gtsamRot2(45*degrees), sqrt(4+4), noiseModel);
graph.addBearingRange(i2, j1, gtsamRot2(90*degrees), 2, noiseModel);
graph.addBearingRange(i3, j2, gtsamRot2(90*degrees), 2, noiseModel);

View File

@ -24,19 +24,19 @@ graph = pose2SLAMGraph;
%% Add prior
% gaussian for prior
priorMean = gtsamPose2(0.0, 0.0, 0.0); % prior at origin
priorNoise = gtsamnoiseModelDiagonal_Sigmas([0.3; 0.3; 0.1]);
priorNoise = gtsamnoiseModelDiagonal.Sigmas([0.3; 0.3; 0.1]);
graph.addPosePrior(1, priorMean, priorNoise); % add directly to graph
%% Add odometry
% general noisemodel for odometry
odometryNoise = gtsamnoiseModelDiagonal_Sigmas([0.2; 0.2; 0.1]);
odometryNoise = gtsamnoiseModelDiagonal.Sigmas([0.2; 0.2; 0.1]);
graph.addRelativePose(1, 2, gtsamPose2(2.0, 0.0, 0.0 ), odometryNoise);
graph.addRelativePose(2, 3, gtsamPose2(2.0, 0.0, pi/2), odometryNoise);
graph.addRelativePose(3, 4, gtsamPose2(2.0, 0.0, pi/2), odometryNoise);
graph.addRelativePose(4, 5, gtsamPose2(2.0, 0.0, pi/2), odometryNoise);
%% Add pose constraint
model = gtsamnoiseModelDiagonal_Sigmas([0.2; 0.2; 0.1]);
model = gtsamnoiseModelDiagonal.Sigmas([0.2; 0.2; 0.1]);
graph.addRelativePose(5, 2, gtsamPose2(2.0, 0.0, pi/2), model);
%% Initialize to noisy points

View File

@ -11,7 +11,7 @@
%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
%% Create a hexagon of poses
hexagon = pose3SLAMValues_Circle(6,1.0);
hexagon = pose3SLAMValues.Circle(6,1.0);
p0 = hexagon.pose(0);
p1 = hexagon.pose(1);
@ -19,7 +19,7 @@ p1 = hexagon.pose(1);
fg = pose3SLAMGraph;
fg.addPoseConstraint(0, p0);
delta = p0.between(p1);
covariance = gtsamnoiseModelDiagonal_Sigmas([0.05; 0.05; 0.05; 5*pi/180; 5*pi/180; 5*pi/180]);
covariance = gtsamnoiseModelDiagonal.Sigmas([0.05; 0.05; 0.05; 5*pi/180; 5*pi/180; 5*pi/180]);
fg.addRelativePose(0,1, delta, covariance);
fg.addRelativePose(1,2, delta, covariance);
fg.addRelativePose(2,3, delta, covariance);

View File

@ -23,7 +23,7 @@ poseNoiseSigmas = [0.001 0.001 0.001 0.1 0.1 0.1]';
graph = visualSLAMGraph;
%% Add factors for all measurements
measurementNoise = gtsamnoiseModelIsotropic_Sigma(2,measurementNoiseSigma);
measurementNoise = gtsamnoiseModelIsotropic.Sigma(2,measurementNoiseSigma);
for i=1:length(data.Z)
for k=1:length(data.Z{i})
j = data.J{i}{k};
@ -31,9 +31,9 @@ for i=1:length(data.Z)
end
end
posePriorNoise = gtsamnoiseModelDiagonal_Sigmas(poseNoiseSigmas);
posePriorNoise = gtsamnoiseModelDiagonal.Sigmas(poseNoiseSigmas);
graph.addPosePrior(symbol('x',1), truth.cameras{1}.pose, posePriorNoise);
pointPriorNoise = gtsamnoiseModelIsotropic_Sigma(3,pointNoiseSigma);
pointPriorNoise = gtsamnoiseModelIsotropic.Sigma(3,pointNoiseSigma);
graph.addPointPrior(symbol('p',1), truth.points{1}, pointPriorNoise);
%% Initial estimate

View File

@ -31,7 +31,7 @@ graph.addPoseConstraint(x1, first_pose);
%% Create realistic calibration and measurement noise model
% format: fx fy skew cx cy baseline
K = gtsamCal3_S2Stereo(1000, 1000, 0, 320, 240, 0.2);
stereo_model = gtsamnoiseModelDiagonal_Sigmas([1.0; 1.0; 1.0]);
stereo_model = gtsamnoiseModelDiagonal.Sigmas([1.0; 1.0; 1.0]);
%% Add measurements
% pose 1

View File

@ -11,9 +11,11 @@ gtsam_assign_source_folders(${wrap_srcs} ${wrap_headers})
add_executable(wrap wrap.cpp)
target_link_libraries(wrap wrap_lib ${Boost_SYSTEM_LIBRARY} ${Boost_FILESYSTEM_LIBRARY})
# Install wrap binary
# Install wrap binary and export target
if (GTSAM_INSTALL_WRAP)
install(TARGETS wrap DESTINATION bin)
install(TARGETS wrap EXPORT GTSAM-exports DESTINATION bin)
list(APPEND GTSAM_EXPORTED_TARGETS wrap)
set(GTSAM_EXPORTED_TARGETS "${GTSAM_EXPORTED_TARGETS}" PARENT_SCOPE)
endif(GTSAM_INSTALL_WRAP)
# Install matlab header

View File

@ -1,176 +1,177 @@
/* ----------------------------------------------------------------------------
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
* Atlanta, Georgia 30332-0415
* All Rights Reserved
* Authors: Frank Dellaert, et al. (see THANKS for the full author list)
* See LICENSE for the license information
* -------------------------------------------------------------------------- */
/**
* @file Class.cpp
* @author Frank Dellaert
* @author Andrew Melim
**/
#include <vector>
#include <iostream>
#include <fstream>
#include <boost/foreach.hpp>
#include <boost/lexical_cast.hpp>
#include "Class.h"
#include "utilities.h"
#include "Argument.h"
using namespace std;
using namespace wrap;
/* ************************************************************************* */
void Class::matlab_proxy(const string& classFile, const string& wrapperName,
const ReturnValue::TypeAttributesTable& typeAttributes,
FileWriter& wrapperFile, vector<string>& functionNames) const {
// open destination classFile
FileWriter proxyFile(classFile, verbose_, "%");
// get the name of actual matlab object
const string matlabName = qualifiedName(), cppName = qualifiedName("::");
const string matlabBaseName = wrap::qualifiedName("", qualifiedParent);
const string cppBaseName = wrap::qualifiedName("::", qualifiedParent);
// emit class proxy code
// we want our class to inherit the handle class for memory purposes
const string parent = qualifiedParent.empty() ?
"handle" : ::wrap::qualifiedName("", qualifiedParent);
proxyFile.oss << "classdef " << matlabName << " < " << parent << endl;
proxyFile.oss << " properties" << endl;
proxyFile.oss << " ptr_" << matlabName << " = 0" << endl;
proxyFile.oss << " end" << endl;
proxyFile.oss << " methods" << endl;
// Constructor
proxyFile.oss << " function obj = " << matlabName << "(varargin)" << endl;
// Special pointer constructors - one in MATLAB to create an object and
// assign a pointer returned from a C++ function. In turn this MATLAB
// constructor calls a special C++ function that just adds the object to
// its collector. This allows wrapped functions to return objects in
// other wrap modules - to add these to their collectors the pointer is
// passed from one C++ module into matlab then back into the other C++
// module.
{
int id = functionNames.size();
const string functionName = pointer_constructor_fragments(proxyFile, wrapperFile, wrapperName, id);
functionNames.push_back(functionName);
}
// Regular constructors
BOOST_FOREACH(ArgumentList a, constructor.args_list)
{
const int id = functionNames.size();
constructor.proxy_fragment(proxyFile, wrapperName, matlabName, matlabBaseName, id, a);
const string wrapFunctionName = constructor.wrapper_fragment(wrapperFile,
cppName, matlabName, cppBaseName, id, using_namespaces, a);
wrapperFile.oss << "\n";
functionNames.push_back(wrapFunctionName);
}
proxyFile.oss << " else\n";
proxyFile.oss << " error('Arguments do not match any overload of " << matlabName << " constructor');" << endl;
proxyFile.oss << " end\n";
if(!qualifiedParent.empty())
proxyFile.oss << " obj = obj@" << matlabBaseName << "(uint64(" << ptr_constructor_key << "), base_ptr);\n";
proxyFile.oss << " obj.ptr_" << matlabName << " = my_ptr;\n";
proxyFile.oss << " end\n\n";
// Deconstructor
{
const int id = functionNames.size();
deconstructor.proxy_fragment(proxyFile, wrapperName, matlabName, id);
proxyFile.oss << "\n";
const string functionName = deconstructor.wrapper_fragment(wrapperFile, cppName, matlabName, id, using_namespaces);
wrapperFile.oss << "\n";
functionNames.push_back(functionName);
}
proxyFile.oss << " function display(obj), obj.print(''); end\n\n";
proxyFile.oss << " function disp(obj), obj.display; end\n\n";
// Methods
BOOST_FOREACH(const Methods::value_type& name_m, methods) {
const Method& m = name_m.second;
m.proxy_wrapper_fragments(proxyFile, wrapperFile, cppName, matlabName, wrapperName, using_namespaces, typeAttributes, functionNames);
proxyFile.oss << "\n";
wrapperFile.oss << "\n";
}
proxyFile.oss << " end\n";
proxyFile.oss << "\n";
proxyFile.oss << " methods(Static = true)\n";
// Static methods
BOOST_FOREACH(const StaticMethods::value_type& name_m, static_methods) {
const StaticMethod& m = name_m.second;
m.proxy_wrapper_fragments(proxyFile, wrapperFile, cppName, matlabName, wrapperName, using_namespaces, typeAttributes, functionNames);
proxyFile.oss << "\n";
wrapperFile.oss << "\n";
}
proxyFile.oss << " end" << endl;
proxyFile.oss << "end" << endl;
// Close file
proxyFile.emit(true);
}
/* ************************************************************************* */
string Class::qualifiedName(const string& delim) const {
return ::wrap::qualifiedName(delim, namespaces, name);
}
/* ************************************************************************* */
string Class::pointer_constructor_fragments(FileWriter& proxyFile, FileWriter& wrapperFile, const string& wrapperName, int id) const {
const string matlabName = qualifiedName(), cppName = qualifiedName("::");
const string wrapFunctionName = matlabName + "_collectorInsertAndMakeBase_" + boost::lexical_cast<string>(id);
const string baseMatlabName = wrap::qualifiedName("", qualifiedParent);
const string baseCppName = wrap::qualifiedName("::", qualifiedParent);
// MATLAB constructor that assigns pointer to matlab object then calls c++
// function to add the object to the collector.
proxyFile.oss << " if nargin == 2 && isa(varargin{1}, 'uint64') && ";
proxyFile.oss << "varargin{1} == uint64(" << ptr_constructor_key << ")\n";
proxyFile.oss << " my_ptr = varargin{2};\n";
if(qualifiedParent.empty()) // If this class has a base class, we'll get a base class pointer back
proxyFile.oss << " ";
else
proxyFile.oss << " base_ptr = ";
proxyFile.oss << wrapperName << "(" << id << ", my_ptr);\n"; // Call collector insert and get base class ptr
// C++ function to add pointer from MATLAB to collector. The pointer always
// comes from a C++ return value; this mechanism allows the object to be added
// to a collector in a different wrap module. If this class has a base class,
// a new pointer to the base class is allocated and returned.
wrapperFile.oss << "void " << wrapFunctionName << "(int nargout, mxArray *out[], int nargin, const mxArray *in[])" << endl;
wrapperFile.oss << "{\n";
wrapperFile.oss << " mexAtExit(&_deleteAllObjects);\n";
generateUsingNamespace(wrapperFile, using_namespaces);
// Typedef boost::shared_ptr
wrapperFile.oss << " typedef boost::shared_ptr<" << cppName << "> Shared;\n";
wrapperFile.oss << "\n";
// Get self pointer passed in
wrapperFile.oss << " Shared *self = *reinterpret_cast<Shared**> (mxGetData(in[0]));\n";
// Add to collector
wrapperFile.oss << " collector_" << matlabName << ".insert(self);\n";
// If we have a base class, return the base class pointer (MATLAB will call the base class collectorInsertAndMakeBase to add this to the collector and recurse the heirarchy)
if(!qualifiedParent.empty()) {
wrapperFile.oss << "\n";
wrapperFile.oss << " typedef boost::shared_ptr<" << baseCppName << "> SharedBase;\n";
/* ----------------------------------------------------------------------------
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
* Atlanta, Georgia 30332-0415
* All Rights Reserved
* Authors: Frank Dellaert, et al. (see THANKS for the full author list)
* See LICENSE for the license information
* -------------------------------------------------------------------------- */
/**
* @file Class.cpp
* @author Frank Dellaert
* @author Andrew Melim
**/
#include <vector>
#include <iostream>
#include <fstream>
#include <cstdint>
#include <boost/foreach.hpp>
#include <boost/lexical_cast.hpp>
#include "Class.h"
#include "utilities.h"
#include "Argument.h"
using namespace std;
using namespace wrap;
/* ************************************************************************* */
void Class::matlab_proxy(const string& classFile, const string& wrapperName,
const ReturnValue::TypeAttributesTable& typeAttributes,
FileWriter& wrapperFile, vector<string>& functionNames) const {
// open destination classFile
FileWriter proxyFile(classFile, verbose_, "%");
// get the name of actual matlab object
const string matlabName = qualifiedName(), cppName = qualifiedName("::");
const string matlabBaseName = wrap::qualifiedName("", qualifiedParent);
const string cppBaseName = wrap::qualifiedName("::", qualifiedParent);
// emit class proxy code
// we want our class to inherit the handle class for memory purposes
const string parent = qualifiedParent.empty() ?
"handle" : ::wrap::qualifiedName("", qualifiedParent);
proxyFile.oss << "classdef " << matlabName << " < " << parent << endl;
proxyFile.oss << " properties" << endl;
proxyFile.oss << " ptr_" << matlabName << " = 0" << endl;
proxyFile.oss << " end" << endl;
proxyFile.oss << " methods" << endl;
// Constructor
proxyFile.oss << " function obj = " << matlabName << "(varargin)" << endl;
// Special pointer constructors - one in MATLAB to create an object and
// assign a pointer returned from a C++ function. In turn this MATLAB
// constructor calls a special C++ function that just adds the object to
// its collector. This allows wrapped functions to return objects in
// other wrap modules - to add these to their collectors the pointer is
// passed from one C++ module into matlab then back into the other C++
// module.
{
int id = functionNames.size();
const string functionName = pointer_constructor_fragments(proxyFile, wrapperFile, wrapperName, id);
functionNames.push_back(functionName);
}
// Regular constructors
BOOST_FOREACH(ArgumentList a, constructor.args_list)
{
const int id = functionNames.size();
constructor.proxy_fragment(proxyFile, wrapperName, matlabName, matlabBaseName, id, a);
const string wrapFunctionName = constructor.wrapper_fragment(wrapperFile,
cppName, matlabName, cppBaseName, id, using_namespaces, a);
wrapperFile.oss << "\n";
functionNames.push_back(wrapFunctionName);
}
proxyFile.oss << " else\n";
proxyFile.oss << " error('Arguments do not match any overload of " << matlabName << " constructor');" << endl;
proxyFile.oss << " end\n";
if(!qualifiedParent.empty())
proxyFile.oss << " obj = obj@" << matlabBaseName << "(uint64(" << ptr_constructor_key << "), base_ptr);\n";
proxyFile.oss << " obj.ptr_" << matlabName << " = my_ptr;\n";
proxyFile.oss << " end\n\n";
// Deconstructor
{
const int id = functionNames.size();
deconstructor.proxy_fragment(proxyFile, wrapperName, matlabName, id);
proxyFile.oss << "\n";
const string functionName = deconstructor.wrapper_fragment(wrapperFile, cppName, matlabName, id, using_namespaces);
wrapperFile.oss << "\n";
functionNames.push_back(functionName);
}
proxyFile.oss << " function display(obj), obj.print(''); end\n\n";
proxyFile.oss << " function disp(obj), obj.display; end\n\n";
// Methods
BOOST_FOREACH(const Methods::value_type& name_m, methods) {
const Method& m = name_m.second;
m.proxy_wrapper_fragments(proxyFile, wrapperFile, cppName, matlabName, wrapperName, using_namespaces, typeAttributes, functionNames);
proxyFile.oss << "\n";
wrapperFile.oss << "\n";
}
proxyFile.oss << " end\n";
proxyFile.oss << "\n";
proxyFile.oss << " methods(Static = true)\n";
// Static methods
BOOST_FOREACH(const StaticMethods::value_type& name_m, static_methods) {
const StaticMethod& m = name_m.second;
m.proxy_wrapper_fragments(proxyFile, wrapperFile, cppName, matlabName, wrapperName, using_namespaces, typeAttributes, functionNames);
proxyFile.oss << "\n";
wrapperFile.oss << "\n";
}
proxyFile.oss << " end" << endl;
proxyFile.oss << "end" << endl;
// Close file
proxyFile.emit(true);
}
/* ************************************************************************* */
string Class::qualifiedName(const string& delim) const {
return ::wrap::qualifiedName(delim, namespaces, name);
}
/* ************************************************************************* */
string Class::pointer_constructor_fragments(FileWriter& proxyFile, FileWriter& wrapperFile, const string& wrapperName, int id) const {
const string matlabName = qualifiedName(), cppName = qualifiedName("::");
const string wrapFunctionName = matlabName + "_collectorInsertAndMakeBase_" + boost::lexical_cast<string>(id);
const string baseMatlabName = wrap::qualifiedName("", qualifiedParent);
const string baseCppName = wrap::qualifiedName("::", qualifiedParent);
// MATLAB constructor that assigns pointer to matlab object then calls c++
// function to add the object to the collector.
proxyFile.oss << " if nargin == 2 && isa(varargin{1}, 'uint64') && ";
proxyFile.oss << "varargin{1} == uint64(" << ptr_constructor_key << ")\n";
proxyFile.oss << " my_ptr = varargin{2};\n";
if(qualifiedParent.empty()) // If this class has a base class, we'll get a base class pointer back
proxyFile.oss << " ";
else
proxyFile.oss << " base_ptr = ";
proxyFile.oss << wrapperName << "(" << id << ", my_ptr);\n"; // Call collector insert and get base class ptr
// C++ function to add pointer from MATLAB to collector. The pointer always
// comes from a C++ return value; this mechanism allows the object to be added
// to a collector in a different wrap module. If this class has a base class,
// a new pointer to the base class is allocated and returned.
wrapperFile.oss << "void " << wrapFunctionName << "(int nargout, mxArray *out[], int nargin, const mxArray *in[])" << endl;
wrapperFile.oss << "{\n";
wrapperFile.oss << " mexAtExit(&_deleteAllObjects);\n";
generateUsingNamespace(wrapperFile, using_namespaces);
// Typedef boost::shared_ptr
wrapperFile.oss << " typedef boost::shared_ptr<" << cppName << "> Shared;\n";
wrapperFile.oss << "\n";
// Get self pointer passed in
wrapperFile.oss << " Shared *self = *reinterpret_cast<Shared**> (mxGetData(in[0]));\n";
// Add to collector
wrapperFile.oss << " collector_" << matlabName << ".insert(self);\n";
// If we have a base class, return the base class pointer (MATLAB will call the base class collectorInsertAndMakeBase to add this to the collector and recurse the heirarchy)
if(!qualifiedParent.empty()) {
wrapperFile.oss << "\n";
wrapperFile.oss << " typedef boost::shared_ptr<" << baseCppName << "> SharedBase;\n";
wrapperFile.oss << " out[0] = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL);\n";
wrapperFile.oss << " *reinterpret_cast<SharedBase**>(mxGetData(out[0])) = new SharedBase(*self);\n";
}
wrapperFile.oss << "}\n";
return wrapFunctionName;
}
/* ************************************************************************* */
wrapperFile.oss << " *reinterpret_cast<SharedBase**>(mxGetData(out[0])) = new SharedBase(*self);\n";
}
wrapperFile.oss << "}\n";
return wrapFunctionName;
}
/* ************************************************************************* */

View File

@ -1,22 +0,0 @@
% automatically generated by wrap
classdef Point2 < handle
properties
self = 0
end
methods
function obj = Point2(varargin)
if (nargin == 0), obj.self = new_Point2(0,0); end
if (nargin == 2 && isa(varargin{1},'double') && isa(varargin{2},'double')), obj.self = new_Point2(0,1,varargin{1},varargin{2}); end
if nargin ==14, new_Point2(varargin{1},0); end
if nargin ~= 13 && nargin ~= 14 && obj.self == 0, error('Point2 constructor failed'); end
end
function delete(obj)
if obj.self ~= 0
new_Point2(obj.self);
obj.self = 0;
end
end
function display(obj), obj.print(''); end
function disp(obj), obj.display; end
end
end

View File

@ -1,11 +0,0 @@
// automatically generated by wrap
#include <wrap/matlab.h>
#include <Point2.h>
typedef boost::shared_ptr<Point2> Shared;
void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
checkArguments("argChar",nargout,nargin-1,1);
Shared obj = unwrap_shared_ptr<Point2>(in[0], "Point2");
char a = unwrap< char >(in[1]);
obj->argChar(a);
}

View File

@ -1,4 +0,0 @@
% result = obj.argChar(a)
function result = argChar(obj,a)
error('need to compile argChar.cpp');
end

View File

@ -1,11 +0,0 @@
// automatically generated by wrap
#include <wrap/matlab.h>
#include <Point2.h>
typedef boost::shared_ptr<Point2> Shared;
void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
checkArguments("argUChar",nargout,nargin-1,1);
Shared obj = unwrap_shared_ptr<Point2>(in[0], "Point2");
unsigned char a = unwrap< unsigned char >(in[1]);
obj->argUChar(a);
}

View File

@ -1,4 +0,0 @@
% result = obj.argUChar(a)
function result = argUChar(obj,a)
error('need to compile argUChar.cpp');
end

View File

@ -1,11 +0,0 @@
// automatically generated by wrap
#include <wrap/matlab.h>
#include <Point2.h>
typedef boost::shared_ptr<Point2> Shared;
void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
checkArguments("dim",nargout,nargin-1,0);
Shared obj = unwrap_shared_ptr<Point2>(in[0], "Point2");
int result = obj->dim();
out[0] = wrap< int >(result);
}

View File

@ -1,4 +0,0 @@
% result = obj.dim()
function result = dim(obj)
error('need to compile dim.cpp');
end

View File

@ -1,11 +0,0 @@
// automatically generated by wrap
#include <wrap/matlab.h>
#include <Point2.h>
typedef boost::shared_ptr<Point2> Shared;
void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
checkArguments("returnChar",nargout,nargin-1,0);
Shared obj = unwrap_shared_ptr<Point2>(in[0], "Point2");
char result = obj->returnChar();
out[0] = wrap< char >(result);
}

View File

@ -1,4 +0,0 @@
% result = obj.returnChar()
function result = returnChar(obj)
error('need to compile returnChar.cpp');
end

View File

@ -1,13 +0,0 @@
// automatically generated by wrap
#include <wrap/matlab.h>
#include <Point2.h>
typedef boost::shared_ptr<VectorNotEigen> SharedVectorNotEigen;
typedef boost::shared_ptr<Point2> Shared;
void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
checkArguments("vectorConfusion",nargout,nargin-1,0);
Shared obj = unwrap_shared_ptr<Point2>(in[0], "Point2");
VectorNotEigen result = obj->vectorConfusion();
SharedVectorNotEigen* ret = new SharedVectorNotEigen(new VectorNotEigen(result));
out[0] = wrap_collect_shared_ptr(ret,"VectorNotEigen");
}

View File

@ -1,4 +0,0 @@
% result = obj.vectorConfusion()
function result = vectorConfusion(obj)
error('need to compile vectorConfusion.cpp');
end

View File

@ -1,11 +0,0 @@
// automatically generated by wrap
#include <wrap/matlab.h>
#include <Point2.h>
typedef boost::shared_ptr<Point2> Shared;
void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
checkArguments("x",nargout,nargin-1,0);
Shared obj = unwrap_shared_ptr<Point2>(in[0], "Point2");
double result = obj->x();
out[0] = wrap< double >(result);
}

View File

@ -1,4 +0,0 @@
% result = obj.x()
function result = x(obj)
error('need to compile x.cpp');
end

View File

@ -1,11 +0,0 @@
// automatically generated by wrap
#include <wrap/matlab.h>
#include <Point2.h>
typedef boost::shared_ptr<Point2> Shared;
void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
checkArguments("y",nargout,nargin-1,0);
Shared obj = unwrap_shared_ptr<Point2>(in[0], "Point2");
double result = obj->y();
out[0] = wrap< double >(result);
}

View File

@ -1,4 +0,0 @@
% result = obj.y()
function result = y(obj)
error('need to compile y.cpp');
end

View File

@ -1,21 +0,0 @@
% automatically generated by wrap
classdef Point3 < handle
properties
self = 0
end
methods
function obj = Point3(varargin)
if (nargin == 3 && isa(varargin{1},'double') && isa(varargin{2},'double') && isa(varargin{3},'double')), obj.self = new_Point3(0,0,varargin{1},varargin{2},varargin{3}); end
if nargin ==14, new_Point3(varargin{1},0); end
if nargin ~= 13 && nargin ~= 14 && obj.self == 0, error('Point3 constructor failed'); end
end
function delete(obj)
if obj.self ~= 0
new_Point3(obj.self);
obj.self = 0;
end
end
function display(obj), obj.print(''); end
function disp(obj), obj.display; end
end
end

View File

@ -1,12 +0,0 @@
// automatically generated by wrap
#include <wrap/matlab.h>
#include <Point3.h>
using namespace geometry;
typedef boost::shared_ptr<Point3> Shared;
void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
checkArguments("norm",nargout,nargin-1,0);
Shared obj = unwrap_shared_ptr<Point3>(in[0], "Point3");
double result = obj->norm();
out[0] = wrap< double >(result);
}

View File

@ -1,4 +0,0 @@
% result = obj.norm()
function result = norm(obj)
error('need to compile norm.cpp');
end

View File

@ -1,22 +0,0 @@
% automatically generated by wrap
classdef Test < handle
properties
self = 0
end
methods
function obj = Test(varargin)
if (nargin == 0), obj.self = new_Test(0,0); end
if (nargin == 2 && isa(varargin{1},'double') && isa(varargin{2},'double')), obj.self = new_Test(0,1,varargin{1},varargin{2}); end
if nargin ==14, new_Test(varargin{1},0); end
if nargin ~= 13 && nargin ~= 14 && obj.self == 0, error('Test constructor failed'); end
end
function delete(obj)
if obj.self ~= 0
new_Test(obj.self);
obj.self = 0;
end
end
function display(obj), obj.print(''); end
function disp(obj), obj.display; end
end
end

View File

@ -1,12 +0,0 @@
// automatically generated by wrap
#include <wrap/matlab.h>
#include <folder/path/to/Test.h>
using namespace geometry;
typedef boost::shared_ptr<Test> Shared;
void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
checkArguments("arg_EigenConstRef",nargout,nargin-1,1);
Shared obj = unwrap_shared_ptr<Test>(in[0], "Test");
Matrix& value = *unwrap_shared_ptr< Matrix >(in[1], "Matrix");
obj->arg_EigenConstRef(value);
}

View File

@ -1,4 +0,0 @@
% result = obj.arg_EigenConstRef(value)
function result = arg_EigenConstRef(obj,value)
error('need to compile arg_EigenConstRef.cpp');
end

View File

@ -1,17 +0,0 @@
// automatically generated by wrap
#include <wrap/matlab.h>
#include <folder/path/to/Test.h>
using namespace geometry;
typedef boost::shared_ptr<Test> SharedTest;
typedef boost::shared_ptr<Test> SharedTest;
typedef boost::shared_ptr<Test> Shared;
void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
checkArguments("create_MixedPtrs",nargout,nargin-1,0);
Shared obj = unwrap_shared_ptr<Test>(in[0], "Test");
pair< Test, SharedTest > result = obj->create_MixedPtrs();
SharedTest* ret = new SharedTest(new Test(result.first));
out[0] = wrap_collect_shared_ptr(ret,"Test");
SharedTest* ret = new SharedTest(result.second);
out[1] = wrap_collect_shared_ptr(ret,"Test");
}

View File

@ -1,4 +0,0 @@
% [first,second] = obj.create_MixedPtrs()
function [first,second] = create_MixedPtrs(obj)
error('need to compile create_MixedPtrs.cpp');
end

View File

@ -1,17 +0,0 @@
// automatically generated by wrap
#include <wrap/matlab.h>
#include <folder/path/to/Test.h>
using namespace geometry;
typedef boost::shared_ptr<Test> SharedTest;
typedef boost::shared_ptr<Test> SharedTest;
typedef boost::shared_ptr<Test> Shared;
void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
checkArguments("create_ptrs",nargout,nargin-1,0);
Shared obj = unwrap_shared_ptr<Test>(in[0], "Test");
pair< SharedTest, SharedTest > result = obj->create_ptrs();
SharedTest* ret = new SharedTest(result.first);
out[0] = wrap_collect_shared_ptr(ret,"Test");
SharedTest* ret = new SharedTest(result.second);
out[1] = wrap_collect_shared_ptr(ret,"Test");
}

View File

@ -1,4 +0,0 @@
% [first,second] = obj.create_ptrs()
function [first,second] = create_ptrs(obj)
error('need to compile create_ptrs.cpp');
end

View File

@ -1,11 +0,0 @@
// automatically generated by wrap
#include <wrap/matlab.h>
#include <folder/path/to/Test.h>
using namespace geometry;
typedef boost::shared_ptr<Test> Shared;
void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
checkArguments("print",nargout,nargin-1,0);
Shared obj = unwrap_shared_ptr<Test>(in[0], "Test");
obj->print();
}

View File

@ -1,4 +0,0 @@
% result = obj.print()
function result = print(obj)
error('need to compile print.cpp');
end

View File

@ -1,15 +0,0 @@
// automatically generated by wrap
#include <wrap/matlab.h>
#include <folder/path/to/Test.h>
using namespace geometry;
typedef boost::shared_ptr<Point2> SharedPoint2;
typedef boost::shared_ptr<Test> Shared;
void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
checkArguments("return_Point2Ptr",nargout,nargin-1,1);
Shared obj = unwrap_shared_ptr<Test>(in[0], "Test");
bool value = unwrap< bool >(in[1]);
SharedPoint2 result = obj->return_Point2Ptr(value);
SharedPoint2* ret = new SharedPoint2(result);
out[0] = wrap_collect_shared_ptr(ret,"Point2");
}

View File

@ -1,4 +0,0 @@
% result = obj.return_Point2Ptr(value)
function result = return_Point2Ptr(obj,value)
error('need to compile return_Point2Ptr.cpp');
end

View File

@ -1,15 +0,0 @@
// automatically generated by wrap
#include <wrap/matlab.h>
#include <folder/path/to/Test.h>
using namespace geometry;
typedef boost::shared_ptr<Test> SharedTest;
typedef boost::shared_ptr<Test> Shared;
void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
checkArguments("return_Test",nargout,nargin-1,1);
Shared obj = unwrap_shared_ptr<Test>(in[0], "Test");
boost::shared_ptr<Test> value = unwrap_shared_ptr< Test >(in[1], "Test");
Test result = obj->return_Test(value);
SharedTest* ret = new SharedTest(new Test(result));
out[0] = wrap_collect_shared_ptr(ret,"Test");
}

View File

@ -1,4 +0,0 @@
% result = obj.return_Test(value)
function result = return_Test(obj,value)
error('need to compile return_Test.cpp');
end

View File

@ -1,15 +0,0 @@
// automatically generated by wrap
#include <wrap/matlab.h>
#include <folder/path/to/Test.h>
using namespace geometry;
typedef boost::shared_ptr<Test> SharedTest;
typedef boost::shared_ptr<Test> Shared;
void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
checkArguments("return_TestPtr",nargout,nargin-1,1);
Shared obj = unwrap_shared_ptr<Test>(in[0], "Test");
boost::shared_ptr<Test> value = unwrap_shared_ptr< Test >(in[1], "Test");
SharedTest result = obj->return_TestPtr(value);
SharedTest* ret = new SharedTest(result);
out[0] = wrap_collect_shared_ptr(ret,"Test");
}

View File

@ -1,4 +0,0 @@
% result = obj.return_TestPtr(value)
function result = return_TestPtr(obj,value)
error('need to compile return_TestPtr.cpp');
end

View File

@ -1,13 +0,0 @@
// automatically generated by wrap
#include <wrap/matlab.h>
#include <folder/path/to/Test.h>
using namespace geometry;
typedef boost::shared_ptr<Test> Shared;
void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
checkArguments("return_bool",nargout,nargin-1,1);
Shared obj = unwrap_shared_ptr<Test>(in[0], "Test");
bool value = unwrap< bool >(in[1]);
bool result = obj->return_bool(value);
out[0] = wrap< bool >(result);
}

View File

@ -1,4 +0,0 @@
% result = obj.return_bool(value)
function result = return_bool(obj,value)
error('need to compile return_bool.cpp');
end

View File

@ -1,13 +0,0 @@
// automatically generated by wrap
#include <wrap/matlab.h>
#include <folder/path/to/Test.h>
using namespace geometry;
typedef boost::shared_ptr<Test> Shared;
void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
checkArguments("return_double",nargout,nargin-1,1);
Shared obj = unwrap_shared_ptr<Test>(in[0], "Test");
double value = unwrap< double >(in[1]);
double result = obj->return_double(value);
out[0] = wrap< double >(result);
}

View File

@ -1,4 +0,0 @@
% result = obj.return_double(value)
function result = return_double(obj,value)
error('need to compile return_double.cpp');
end

View File

@ -1,13 +0,0 @@
// automatically generated by wrap
#include <wrap/matlab.h>
#include <folder/path/to/Test.h>
using namespace geometry;
typedef boost::shared_ptr<Test> Shared;
void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
checkArguments("return_field",nargout,nargin-1,1);
Shared obj = unwrap_shared_ptr<Test>(in[0], "Test");
Test& t = *unwrap_shared_ptr< Test >(in[1], "Test");
bool result = obj->return_field(t);
out[0] = wrap< bool >(result);
}

View File

@ -1,4 +0,0 @@
% result = obj.return_field(t)
function result = return_field(obj,t)
error('need to compile return_field.cpp');
end

View File

@ -1,13 +0,0 @@
// automatically generated by wrap
#include <wrap/matlab.h>
#include <folder/path/to/Test.h>
using namespace geometry;
typedef boost::shared_ptr<Test> Shared;
void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
checkArguments("return_int",nargout,nargin-1,1);
Shared obj = unwrap_shared_ptr<Test>(in[0], "Test");
int value = unwrap< int >(in[1]);
int result = obj->return_int(value);
out[0] = wrap< int >(result);
}

View File

@ -1,4 +0,0 @@
% result = obj.return_int(value)
function result = return_int(obj,value)
error('need to compile return_int.cpp');
end

View File

@ -1,13 +0,0 @@
// automatically generated by wrap
#include <wrap/matlab.h>
#include <folder/path/to/Test.h>
using namespace geometry;
typedef boost::shared_ptr<Test> Shared;
void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
checkArguments("return_matrix1",nargout,nargin-1,1);
Shared obj = unwrap_shared_ptr<Test>(in[0], "Test");
Matrix value = unwrap< Matrix >(in[1]);
Matrix result = obj->return_matrix1(value);
out[0] = wrap< Matrix >(result);
}

View File

@ -1,4 +0,0 @@
% result = obj.return_matrix1(value)
function result = return_matrix1(obj,value)
error('need to compile return_matrix1.cpp');
end

View File

@ -1,13 +0,0 @@
// automatically generated by wrap
#include <wrap/matlab.h>
#include <folder/path/to/Test.h>
using namespace geometry;
typedef boost::shared_ptr<Test> Shared;
void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
checkArguments("return_matrix2",nargout,nargin-1,1);
Shared obj = unwrap_shared_ptr<Test>(in[0], "Test");
Matrix value = unwrap< Matrix >(in[1]);
Matrix result = obj->return_matrix2(value);
out[0] = wrap< Matrix >(result);
}

View File

@ -1,4 +0,0 @@
% result = obj.return_matrix2(value)
function result = return_matrix2(obj,value)
error('need to compile return_matrix2.cpp');
end

View File

@ -1,15 +0,0 @@
// automatically generated by wrap
#include <wrap/matlab.h>
#include <folder/path/to/Test.h>
using namespace geometry;
typedef boost::shared_ptr<Test> Shared;
void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
checkArguments("return_pair",nargout,nargin-1,2);
Shared obj = unwrap_shared_ptr<Test>(in[0], "Test");
Vector v = unwrap< Vector >(in[1]);
Matrix A = unwrap< Matrix >(in[2]);
pair< Vector, Matrix > result = obj->return_pair(v,A);
out[0] = wrap< Vector >(result.first);
out[1] = wrap< Matrix >(result.second);
}

View File

@ -1,4 +0,0 @@
% [first,second] = obj.return_pair(v,A)
function [first,second] = return_pair(obj,v,A)
error('need to compile return_pair.cpp');
end

View File

@ -1,19 +0,0 @@
// automatically generated by wrap
#include <wrap/matlab.h>
#include <folder/path/to/Test.h>
using namespace geometry;
typedef boost::shared_ptr<Test> SharedTest;
typedef boost::shared_ptr<Test> SharedTest;
typedef boost::shared_ptr<Test> Shared;
void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
checkArguments("return_ptrs",nargout,nargin-1,2);
Shared obj = unwrap_shared_ptr<Test>(in[0], "Test");
boost::shared_ptr<Test> p1 = unwrap_shared_ptr< Test >(in[1], "Test");
boost::shared_ptr<Test> p2 = unwrap_shared_ptr< Test >(in[2], "Test");
pair< SharedTest, SharedTest > result = obj->return_ptrs(p1,p2);
SharedTest* ret = new SharedTest(result.first);
out[0] = wrap_collect_shared_ptr(ret,"Test");
SharedTest* ret = new SharedTest(result.second);
out[1] = wrap_collect_shared_ptr(ret,"Test");
}

View File

@ -1,4 +0,0 @@
% [first,second] = obj.return_ptrs(p1,p2)
function [first,second] = return_ptrs(obj,p1,p2)
error('need to compile return_ptrs.cpp');
end

View File

@ -1,13 +0,0 @@
// automatically generated by wrap
#include <wrap/matlab.h>
#include <folder/path/to/Test.h>
using namespace geometry;
typedef boost::shared_ptr<Test> Shared;
void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
checkArguments("return_size_t",nargout,nargin-1,1);
Shared obj = unwrap_shared_ptr<Test>(in[0], "Test");
size_t value = unwrap< size_t >(in[1]);
size_t result = obj->return_size_t(value);
out[0] = wrap< size_t >(result);
}

View File

@ -1,4 +0,0 @@
% result = obj.return_size_t(value)
function result = return_size_t(obj,value)
error('need to compile return_size_t.cpp');
end

View File

@ -1,13 +0,0 @@
// automatically generated by wrap
#include <wrap/matlab.h>
#include <folder/path/to/Test.h>
using namespace geometry;
typedef boost::shared_ptr<Test> Shared;
void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
checkArguments("return_string",nargout,nargin-1,1);
Shared obj = unwrap_shared_ptr<Test>(in[0], "Test");
string value = unwrap< string >(in[1]);
string result = obj->return_string(value);
out[0] = wrap< string >(result);
}

View File

@ -1,4 +0,0 @@
% result = obj.return_string(value)
function result = return_string(obj,value)
error('need to compile return_string.cpp');
end

View File

@ -1,13 +0,0 @@
// automatically generated by wrap
#include <wrap/matlab.h>
#include <folder/path/to/Test.h>
using namespace geometry;
typedef boost::shared_ptr<Test> Shared;
void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
checkArguments("return_vector1",nargout,nargin-1,1);
Shared obj = unwrap_shared_ptr<Test>(in[0], "Test");
Vector value = unwrap< Vector >(in[1]);
Vector result = obj->return_vector1(value);
out[0] = wrap< Vector >(result);
}

View File

@ -1,4 +0,0 @@
% result = obj.return_vector1(value)
function result = return_vector1(obj,value)
error('need to compile return_vector1.cpp');
end

View File

@ -1,13 +0,0 @@
// automatically generated by wrap
#include <wrap/matlab.h>
#include <folder/path/to/Test.h>
using namespace geometry;
typedef boost::shared_ptr<Test> Shared;
void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
checkArguments("return_vector2",nargout,nargin-1,1);
Shared obj = unwrap_shared_ptr<Test>(in[0], "Test");
Vector value = unwrap< Vector >(in[1]);
Vector result = obj->return_vector2(value);
out[0] = wrap< Vector >(result);
}

View File

@ -1,4 +0,0 @@
% result = obj.return_vector2(value)
function result = return_vector2(obj,value)
error('need to compile return_vector2.cpp');
end

View File

@ -1,94 +0,0 @@
# automatically generated by wrap
MEX = mex
MEXENDING = mexa64
PATH_TO_WRAP = /not_really_a_real_path/borg/gtsam/wrap
mex_flags = -O5
all: Point2 Point3 Test
# Point2
new_Point2.$(MEXENDING): new_Point2.cpp $(PATH_TO_WRAP)/matlab.h
$(MEX) $(mex_flags) new_Point2.cpp -output new_Point2
@Point2/x.$(MEXENDING): @Point2/x.cpp $(PATH_TO_WRAP)/matlab.h
$(MEX) $(mex_flags) @Point2/x.cpp -output @Point2/x
@Point2/y.$(MEXENDING): @Point2/y.cpp $(PATH_TO_WRAP)/matlab.h
$(MEX) $(mex_flags) @Point2/y.cpp -output @Point2/y
@Point2/dim.$(MEXENDING): @Point2/dim.cpp $(PATH_TO_WRAP)/matlab.h
$(MEX) $(mex_flags) @Point2/dim.cpp -output @Point2/dim
@Point2/returnChar.$(MEXENDING): @Point2/returnChar.cpp $(PATH_TO_WRAP)/matlab.h
$(MEX) $(mex_flags) @Point2/returnChar.cpp -output @Point2/returnChar
@Point2/argChar.$(MEXENDING): @Point2/argChar.cpp $(PATH_TO_WRAP)/matlab.h
$(MEX) $(mex_flags) @Point2/argChar.cpp -output @Point2/argChar
@Point2/argUChar.$(MEXENDING): @Point2/argUChar.cpp $(PATH_TO_WRAP)/matlab.h
$(MEX) $(mex_flags) @Point2/argUChar.cpp -output @Point2/argUChar
@Point2/vectorConfusion.$(MEXENDING): @Point2/vectorConfusion.cpp $(PATH_TO_WRAP)/matlab.h
$(MEX) $(mex_flags) @Point2/vectorConfusion.cpp -output @Point2/vectorConfusion
Point2: new_Point2.$(MEXENDING) @Point2/x.$(MEXENDING) @Point2/y.$(MEXENDING) @Point2/dim.$(MEXENDING) @Point2/returnChar.$(MEXENDING) @Point2/argChar.$(MEXENDING) @Point2/argUChar.$(MEXENDING) @Point2/vectorConfusion.$(MEXENDING)
# Point3
new_Point3.$(MEXENDING): new_Point3.cpp $(PATH_TO_WRAP)/matlab.h
$(MEX) $(mex_flags) new_Point3.cpp -output new_Point3
Point3_staticFunction.$(MEXENDING): Point3_staticFunction.cpp $(PATH_TO_WRAP)/matlab.h
$(MEX) $(mex_flags) Point3_staticFunction.cpp -output Point3_staticFunction
Point3_StaticFunctionRet.$(MEXENDING): Point3_StaticFunctionRet.cpp $(PATH_TO_WRAP)/matlab.h
$(MEX) $(mex_flags) Point3_StaticFunctionRet.cpp -output Point3_StaticFunctionRet
@Point3/norm.$(MEXENDING): @Point3/norm.cpp $(PATH_TO_WRAP)/matlab.h
$(MEX) $(mex_flags) @Point3/norm.cpp -output @Point3/norm
Point3: new_Point3.$(MEXENDING) Point3_staticFunction.$(MEXENDING) Point3_StaticFunctionRet.$(MEXENDING) @Point3/norm.$(MEXENDING)
# Test
new_Test.$(MEXENDING): new_Test.cpp $(PATH_TO_WRAP)/matlab.h
$(MEX) $(mex_flags) new_Test.cpp -output new_Test
@Test/return_pair.$(MEXENDING): @Test/return_pair.cpp $(PATH_TO_WRAP)/matlab.h
$(MEX) $(mex_flags) @Test/return_pair.cpp -output @Test/return_pair
@Test/return_bool.$(MEXENDING): @Test/return_bool.cpp $(PATH_TO_WRAP)/matlab.h
$(MEX) $(mex_flags) @Test/return_bool.cpp -output @Test/return_bool
@Test/return_size_t.$(MEXENDING): @Test/return_size_t.cpp $(PATH_TO_WRAP)/matlab.h
$(MEX) $(mex_flags) @Test/return_size_t.cpp -output @Test/return_size_t
@Test/return_int.$(MEXENDING): @Test/return_int.cpp $(PATH_TO_WRAP)/matlab.h
$(MEX) $(mex_flags) @Test/return_int.cpp -output @Test/return_int
@Test/return_double.$(MEXENDING): @Test/return_double.cpp $(PATH_TO_WRAP)/matlab.h
$(MEX) $(mex_flags) @Test/return_double.cpp -output @Test/return_double
@Test/return_string.$(MEXENDING): @Test/return_string.cpp $(PATH_TO_WRAP)/matlab.h
$(MEX) $(mex_flags) @Test/return_string.cpp -output @Test/return_string
@Test/return_vector1.$(MEXENDING): @Test/return_vector1.cpp $(PATH_TO_WRAP)/matlab.h
$(MEX) $(mex_flags) @Test/return_vector1.cpp -output @Test/return_vector1
@Test/return_matrix1.$(MEXENDING): @Test/return_matrix1.cpp $(PATH_TO_WRAP)/matlab.h
$(MEX) $(mex_flags) @Test/return_matrix1.cpp -output @Test/return_matrix1
@Test/return_vector2.$(MEXENDING): @Test/return_vector2.cpp $(PATH_TO_WRAP)/matlab.h
$(MEX) $(mex_flags) @Test/return_vector2.cpp -output @Test/return_vector2
@Test/return_matrix2.$(MEXENDING): @Test/return_matrix2.cpp $(PATH_TO_WRAP)/matlab.h
$(MEX) $(mex_flags) @Test/return_matrix2.cpp -output @Test/return_matrix2
@Test/arg_EigenConstRef.$(MEXENDING): @Test/arg_EigenConstRef.cpp $(PATH_TO_WRAP)/matlab.h
$(MEX) $(mex_flags) @Test/arg_EigenConstRef.cpp -output @Test/arg_EigenConstRef
@Test/return_field.$(MEXENDING): @Test/return_field.cpp $(PATH_TO_WRAP)/matlab.h
$(MEX) $(mex_flags) @Test/return_field.cpp -output @Test/return_field
@Test/return_TestPtr.$(MEXENDING): @Test/return_TestPtr.cpp $(PATH_TO_WRAP)/matlab.h
$(MEX) $(mex_flags) @Test/return_TestPtr.cpp -output @Test/return_TestPtr
@Test/return_Test.$(MEXENDING): @Test/return_Test.cpp $(PATH_TO_WRAP)/matlab.h
$(MEX) $(mex_flags) @Test/return_Test.cpp -output @Test/return_Test
@Test/return_Point2Ptr.$(MEXENDING): @Test/return_Point2Ptr.cpp $(PATH_TO_WRAP)/matlab.h
$(MEX) $(mex_flags) @Test/return_Point2Ptr.cpp -output @Test/return_Point2Ptr
@Test/create_ptrs.$(MEXENDING): @Test/create_ptrs.cpp $(PATH_TO_WRAP)/matlab.h
$(MEX) $(mex_flags) @Test/create_ptrs.cpp -output @Test/create_ptrs
@Test/create_MixedPtrs.$(MEXENDING): @Test/create_MixedPtrs.cpp $(PATH_TO_WRAP)/matlab.h
$(MEX) $(mex_flags) @Test/create_MixedPtrs.cpp -output @Test/create_MixedPtrs
@Test/return_ptrs.$(MEXENDING): @Test/return_ptrs.cpp $(PATH_TO_WRAP)/matlab.h
$(MEX) $(mex_flags) @Test/return_ptrs.cpp -output @Test/return_ptrs
@Test/print.$(MEXENDING): @Test/print.cpp $(PATH_TO_WRAP)/matlab.h
$(MEX) $(mex_flags) @Test/print.cpp -output @Test/print
Test: new_Test.$(MEXENDING) @Test/return_pair.$(MEXENDING) @Test/return_bool.$(MEXENDING) @Test/return_size_t.$(MEXENDING) @Test/return_int.$(MEXENDING) @Test/return_double.$(MEXENDING) @Test/return_string.$(MEXENDING) @Test/return_vector1.$(MEXENDING) @Test/return_matrix1.$(MEXENDING) @Test/return_vector2.$(MEXENDING) @Test/return_matrix2.$(MEXENDING) @Test/arg_EigenConstRef.$(MEXENDING) @Test/return_field.$(MEXENDING) @Test/return_TestPtr.$(MEXENDING) @Test/return_Test.$(MEXENDING) @Test/return_Point2Ptr.$(MEXENDING) @Test/create_ptrs.$(MEXENDING) @Test/create_MixedPtrs.$(MEXENDING) @Test/return_ptrs.$(MEXENDING) @Test/print.$(MEXENDING)
clean:
rm -rf *.$(MEXENDING)
rm -rf @Point2/*.$(MEXENDING)
rm -rf @Point3/*.$(MEXENDING)
rm -rf @Test/*.$(MEXENDING)

View File

@ -0,0 +1,88 @@
% automatically generated by wrap
classdef Point2 < handle
properties
self = 0
end
methods
function obj = Point2(varargin)
if nargin == 2 && isa(varargin{1}, 'uint64') && varargin{1} == uint64(5139824614673773682)
obj.self = varargin{2};
geometry_wrapper(obj.self);
elseif nargin == 0
obj.self = geometry_wrapper(1);
elseif nargin == 2 && isa(varargin{1},'double') && isa(varargin{2},'double')
obj.self = geometry_wrapper(2,varargin{1},varargin{2});
else
error('Arguments do not match any overload of Point2 constructor');
end
end
function delete(obj)
geometry_wrapper(3, obj.self);
end
function display(obj), obj.print(''); end
function disp(obj), obj.display; end
function varargout = argChar(self, varargin)
if length(varargin) == 1 && isa(varargin{1},'char')
geometry_wrapper(4, self, varargin{:});
else
error('Arguments do not match any overload of function Point2.argChar');
end
end
function varargout = argUChar(self, varargin)
if length(varargin) == 1 && isa(varargin{1},'char')
geometry_wrapper(5, self, varargin{:});
else
error('Arguments do not match any overload of function Point2.argUChar');
end
end
function varargout = dim(self, varargin)
if length(varargin) == 0
varargout{1} = geometry_wrapper(6, self, varargin{:});
else
error('Arguments do not match any overload of function Point2.dim');
end
end
function varargout = returnChar(self, varargin)
if length(varargin) == 0
varargout{1} = geometry_wrapper(7, self, varargin{:});
else
error('Arguments do not match any overload of function Point2.returnChar');
end
end
function varargout = vectorConfusion(self, varargin)
if length(varargin) == 0
varargout{1} = geometry_wrapper(8, self, varargin{:});
else
error('Arguments do not match any overload of function Point2.vectorConfusion');
end
end
function varargout = x(self, varargin)
if length(varargin) == 0
varargout{1} = geometry_wrapper(9, self, varargin{:});
else
error('Arguments do not match any overload of function Point2.x');
end
end
function varargout = y(self, varargin)
if length(varargin) == 0
varargout{1} = geometry_wrapper(10, self, varargin{:});
else
error('Arguments do not match any overload of function Point2.y');
end
end
end
methods(Static = true)
end
end

View File

@ -0,0 +1,54 @@
% automatically generated by wrap
classdef Point3 < handle
properties
self = 0
end
methods
function obj = Point3(varargin)
if nargin == 2 && isa(varargin{1}, 'uint64') && varargin{1} == uint64(5139824614673773682)
obj.self = varargin{2};
geometry_wrapper(obj.self);
elseif nargin == 3 && isa(varargin{1},'double') && isa(varargin{2},'double') && isa(varargin{3},'double')
obj.self = geometry_wrapper(12,varargin{1},varargin{2},varargin{3});
else
error('Arguments do not match any overload of Point3 constructor');
end
end
function delete(obj)
geometry_wrapper(13, obj.self);
end
function display(obj), obj.print(''); end
function disp(obj), obj.display; end
function varargout = norm(self, varargin)
if length(varargin) == 0
varargout{1} = geometry_wrapper(14, self, varargin{:});
else
error('Arguments do not match any overload of function Point3.norm');
end
end
end
methods(Static = true)
function varargout = StaticFunctionRet(varargin)
if length(varargin) == 1 && isa(varargin{1},'double')
varargout{1} = geometry_wrapper(15, varargin{:});
else
error('Arguments do not match any overload of function Point3.StaticFunctionRet');
end
end
function varargout = StaticFunction(varargin)
if length(varargin) == 0
varargout{1} = geometry_wrapper(16, varargin{:});
else
error('Arguments do not match any overload of function Point3.StaticFunction');
end
end
end
end

View File

@ -1,14 +0,0 @@
// automatically generated by wrap
#include <wrap/matlab.h>
#include <Point3.h>
using namespace geometry;
typedef boost::shared_ptr<Point3> SharedPoint3;
typedef boost::shared_ptr<Point3> Shared;
void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
checkArguments("Point3_StaticFunctionRet",nargout,nargin,1);
double z = unwrap< double >(in[0]);
Point3 result = Point3::StaticFunctionRet(z);
SharedPoint3* ret = new SharedPoint3(new Point3(result));
out[0] = wrap_collect_shared_ptr(ret,"Point3");
}

View File

@ -1,5 +0,0 @@
% automatically generated by wrap
function result = Point3_StaticFunctionRet(z)
% usage: x = Point3_StaticFunctionRet(z)
error('need to compile Point3_StaticFunctionRet.cpp');
end

View File

@ -1,12 +0,0 @@
// automatically generated by wrap
#include <wrap/matlab.h>
#include <Point3.h>
using namespace geometry;
typedef boost::shared_ptr<double> Shareddouble;
typedef boost::shared_ptr<Point3> Shared;
void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
checkArguments("Point3_staticFunction",nargout,nargin,0);
double result = Point3::staticFunction();
out[0] = wrap< double >(result);
}

View File

@ -1,5 +0,0 @@
% automatically generated by wrap
function result = Point3_staticFunction()
% usage: x = Point3_staticFunction()
error('need to compile Point3_staticFunction.cpp');
end

184
wrap/tests/expected/Test.m Normal file
View File

@ -0,0 +1,184 @@
% automatically generated by wrap
classdef Test < handle
properties
self = 0
end
methods
function obj = Test(varargin)
if nargin == 2 && isa(varargin{1}, 'uint64') && varargin{1} == uint64(5139824614673773682)
obj.self = varargin{2};
geometry_wrapper(obj.self);
elseif nargin == 0
obj.self = geometry_wrapper(18);
elseif nargin == 2 && isa(varargin{1},'double') && isa(varargin{2},'double')
obj.self = geometry_wrapper(19,varargin{1},varargin{2});
else
error('Arguments do not match any overload of Test constructor');
end
end
function delete(obj)
geometry_wrapper(20, obj.self);
end
function display(obj), obj.print(''); end
function disp(obj), obj.display; end
function varargout = arg_EigenConstRef(self, varargin)
if length(varargin) == 1 && isa(varargin{1},'double')
geometry_wrapper(21, self, varargin{:});
else
error('Arguments do not match any overload of function Test.arg_EigenConstRef');
end
end
function varargout = create_MixedPtrs(self, varargin)
if length(varargin) == 0
[ varargout{1} varargout{2} ] = geometry_wrapper(22, self, varargin{:});
else
error('Arguments do not match any overload of function Test.create_MixedPtrs');
end
end
function varargout = create_ptrs(self, varargin)
if length(varargin) == 0
[ varargout{1} varargout{2} ] = geometry_wrapper(23, self, varargin{:});
else
error('Arguments do not match any overload of function Test.create_ptrs');
end
end
function varargout = print(self, varargin)
if length(varargin) == 0
geometry_wrapper(24, self, varargin{:});
else
error('Arguments do not match any overload of function Test.print');
end
end
function varargout = return_Point2Ptr(self, varargin)
if length(varargin) == 1 && isa(varargin{1},'logical')
varargout{1} = geometry_wrapper(25, self, varargin{:});
else
error('Arguments do not match any overload of function Test.return_Point2Ptr');
end
end
function varargout = return_Test(self, varargin)
if length(varargin) == 1 && isa(varargin{1},'Test')
varargout{1} = geometry_wrapper(26, self, varargin{:});
else
error('Arguments do not match any overload of function Test.return_Test');
end
end
function varargout = return_TestPtr(self, varargin)
if length(varargin) == 1 && isa(varargin{1},'Test')
varargout{1} = geometry_wrapper(27, self, varargin{:});
else
error('Arguments do not match any overload of function Test.return_TestPtr');
end
end
function varargout = return_bool(self, varargin)
if length(varargin) == 1 && isa(varargin{1},'logical')
varargout{1} = geometry_wrapper(28, self, varargin{:});
else
error('Arguments do not match any overload of function Test.return_bool');
end
end
function varargout = return_double(self, varargin)
if length(varargin) == 1 && isa(varargin{1},'double')
varargout{1} = geometry_wrapper(29, self, varargin{:});
else
error('Arguments do not match any overload of function Test.return_double');
end
end
function varargout = return_field(self, varargin)
if length(varargin) == 1 && isa(varargin{1},'Test')
varargout{1} = geometry_wrapper(30, self, varargin{:});
else
error('Arguments do not match any overload of function Test.return_field');
end
end
function varargout = return_int(self, varargin)
if length(varargin) == 1 && isa(varargin{1},'numeric')
varargout{1} = geometry_wrapper(31, self, varargin{:});
else
error('Arguments do not match any overload of function Test.return_int');
end
end
function varargout = return_matrix1(self, varargin)
if length(varargin) == 1 && isa(varargin{1},'double')
varargout{1} = geometry_wrapper(32, self, varargin{:});
else
error('Arguments do not match any overload of function Test.return_matrix1');
end
end
function varargout = return_matrix2(self, varargin)
if length(varargin) == 1 && isa(varargin{1},'double')
varargout{1} = geometry_wrapper(33, self, varargin{:});
else
error('Arguments do not match any overload of function Test.return_matrix2');
end
end
function varargout = return_pair(self, varargin)
if length(varargin) == 2 && isa(varargin{1},'double') && isa(varargin{2},'double')
[ varargout{1} varargout{2} ] = geometry_wrapper(34, self, varargin{:});
else
error('Arguments do not match any overload of function Test.return_pair');
end
end
function varargout = return_ptrs(self, varargin)
if length(varargin) == 2 && isa(varargin{1},'Test') && isa(varargin{2},'Test')
[ varargout{1} varargout{2} ] = geometry_wrapper(35, self, varargin{:});
else
error('Arguments do not match any overload of function Test.return_ptrs');
end
end
function varargout = return_size_t(self, varargin)
if length(varargin) == 1 && isa(varargin{1},'numeric')
varargout{1} = geometry_wrapper(36, self, varargin{:});
else
error('Arguments do not match any overload of function Test.return_size_t');
end
end
function varargout = return_string(self, varargin)
if length(varargin) == 1 && isa(varargin{1},'char')
varargout{1} = geometry_wrapper(37, self, varargin{:});
else
error('Arguments do not match any overload of function Test.return_string');
end
end
function varargout = return_vector1(self, varargin)
if length(varargin) == 1 && isa(varargin{1},'double')
varargout{1} = geometry_wrapper(38, self, varargin{:});
else
error('Arguments do not match any overload of function Test.return_vector1');
end
end
function varargout = return_vector2(self, varargin)
if length(varargin) == 1 && isa(varargin{1},'double')
varargout{1} = geometry_wrapper(39, self, varargin{:});
else
error('Arguments do not match any overload of function Test.return_vector2');
end
end
end
methods(Static = true)
end
end

View File

@ -0,0 +1,621 @@
// automatically generated by wrap
#include <wrap/matlab.h>
#include <map>
#include <boost/foreach.hpp>
#include <Point2.h>
#include <Point3.h>
#include <folder/path/to/Test.h>
typedef std::set<boost::shared_ptr<Point2>*> Collector_Point2;
static Collector_Point2 collector_Point2;
typedef std::set<boost::shared_ptr<Point3>*> Collector_Point3;
static Collector_Point3 collector_Point3;
typedef std::set<boost::shared_ptr<Test>*> Collector_Test;
static Collector_Test collector_Test;
void _deleteAllObjects()
{
for(Collector_Point2::iterator iter = collector_Point2.begin();
iter != collector_Point2.end(); ) {
delete *iter;
collector_Point2.erase(iter++);
}
for(Collector_Point3::iterator iter = collector_Point3.begin();
iter != collector_Point3.end(); ) {
delete *iter;
collector_Point3.erase(iter++);
}
for(Collector_Test::iterator iter = collector_Test.begin();
iter != collector_Test.end(); ) {
delete *iter;
collector_Test.erase(iter++);
}
}
void Point2_constructor_0(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
mexAtExit(&_deleteAllObjects);
typedef boost::shared_ptr<Point2> Shared;
Shared *self = *reinterpret_cast<Shared**> (mxGetData(in[0]));
collector_Point2.insert(self);
}
void Point2_constructor_1(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
mexAtExit(&_deleteAllObjects);
typedef boost::shared_ptr<Point2> Shared;
Shared *self = new Shared(new Point2());
collector_Point2.insert(self);
out[0] = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL);
*reinterpret_cast<Shared**> (mxGetData(out[0])) = self;
}
void Point2_constructor_2(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
mexAtExit(&_deleteAllObjects);
typedef boost::shared_ptr<Point2> Shared;
double x = unwrap< double >(in[0]);
double y = unwrap< double >(in[1]);
Shared *self = new Shared(new Point2(x,y));
collector_Point2.insert(self);
out[0] = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL);
*reinterpret_cast<Shared**> (mxGetData(out[0])) = self;
}
void Point2_deconstructor_3(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
typedef boost::shared_ptr<Point2> Shared;
checkArguments("delete_Point2",nargout,nargin,1);
Shared *self = *reinterpret_cast<Shared**>(mxGetData(in[0]));
Collector_Point2::iterator item;
item = collector_Point2.find(self);
if(item != collector_Point2.end()) {
delete self;
collector_Point2.erase(item);
}
}
void Point2_argChar_4(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
typedef boost::shared_ptr<Point2> Shared;
checkArguments("argChar",nargout,nargin-1,1);
Shared obj = unwrap_shared_ptr<Point2>(in[0], "Point2");
char a = unwrap< char >(in[1]);
obj->argChar(a);
}
void Point2_argUChar_5(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
typedef boost::shared_ptr<Point2> Shared;
checkArguments("argUChar",nargout,nargin-1,1);
Shared obj = unwrap_shared_ptr<Point2>(in[0], "Point2");
unsigned char a = unwrap< unsigned char >(in[1]);
obj->argUChar(a);
}
void Point2_dim_6(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
typedef boost::shared_ptr<Point2> Shared;
checkArguments("dim",nargout,nargin-1,0);
Shared obj = unwrap_shared_ptr<Point2>(in[0], "Point2");
int result = obj->dim();
out[0] = wrap< int >(result);
}
void Point2_returnChar_7(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
typedef boost::shared_ptr<Point2> Shared;
checkArguments("returnChar",nargout,nargin-1,0);
Shared obj = unwrap_shared_ptr<Point2>(in[0], "Point2");
char result = obj->returnChar();
out[0] = wrap< char >(result);
}
void Point2_vectorConfusion_8(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
typedef boost::shared_ptr<VectorNotEigen> SharedVectorNotEigen;
typedef boost::shared_ptr<Point2> Shared;
checkArguments("vectorConfusion",nargout,nargin-1,0);
Shared obj = unwrap_shared_ptr<Point2>(in[0], "Point2");
VectorNotEigen result = obj->vectorConfusion();
SharedVectorNotEigen* ret = new SharedVectorNotEigen(new VectorNotEigen(result));
out[0] = wrap_shared_ptr(ret,"VectorNotEigen");
}
void Point2_x_9(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
typedef boost::shared_ptr<Point2> Shared;
checkArguments("x",nargout,nargin-1,0);
Shared obj = unwrap_shared_ptr<Point2>(in[0], "Point2");
double result = obj->x();
out[0] = wrap< double >(result);
}
void Point2_y_10(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
typedef boost::shared_ptr<Point2> Shared;
checkArguments("y",nargout,nargin-1,0);
Shared obj = unwrap_shared_ptr<Point2>(in[0], "Point2");
double result = obj->y();
out[0] = wrap< double >(result);
}
void Point3_constructor_11(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
mexAtExit(&_deleteAllObjects);
using namespace geometry;
typedef boost::shared_ptr<Point3> Shared;
Shared *self = *reinterpret_cast<Shared**> (mxGetData(in[0]));
collector_Point3.insert(self);
}
void Point3_constructor_12(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
mexAtExit(&_deleteAllObjects);
using namespace geometry;
typedef boost::shared_ptr<Point3> Shared;
double x = unwrap< double >(in[0]);
double y = unwrap< double >(in[1]);
double z = unwrap< double >(in[2]);
Shared *self = new Shared(new Point3(x,y,z));
collector_Point3.insert(self);
out[0] = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL);
*reinterpret_cast<Shared**> (mxGetData(out[0])) = self;
}
void Point3_deconstructor_13(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
using namespace geometry;
typedef boost::shared_ptr<Point3> Shared;
checkArguments("delete_Point3",nargout,nargin,1);
Shared *self = *reinterpret_cast<Shared**>(mxGetData(in[0]));
Collector_Point3::iterator item;
item = collector_Point3.find(self);
if(item != collector_Point3.end()) {
delete self;
collector_Point3.erase(item);
}
}
void Point3_norm_14(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
using namespace geometry;
typedef boost::shared_ptr<Point3> Shared;
checkArguments("norm",nargout,nargin-1,0);
Shared obj = unwrap_shared_ptr<Point3>(in[0], "Point3");
double result = obj->norm();
out[0] = wrap< double >(result);
}
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> Shared;
checkArguments("Point3.StaticFunctionRet",nargout,nargin,1);
double z = unwrap< double >(in[0]);
Point3 result = Point3::StaticFunctionRet(z);
SharedPoint3* ret = new SharedPoint3(new Point3(result));
out[0] = wrap_shared_ptr(ret,"Point3");
}
void Point3_staticFunction_16(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
using namespace geometry;
typedef boost::shared_ptr<Point3> Shared;
checkArguments("Point3.staticFunction",nargout,nargin,0);
double result = Point3::staticFunction();
out[0] = wrap< double >(result);
}
void Test_constructor_17(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
mexAtExit(&_deleteAllObjects);
using namespace geometry;
typedef boost::shared_ptr<Test> Shared;
Shared *self = *reinterpret_cast<Shared**> (mxGetData(in[0]));
collector_Test.insert(self);
}
void Test_constructor_18(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
mexAtExit(&_deleteAllObjects);
using namespace geometry;
typedef boost::shared_ptr<Test> Shared;
Shared *self = new Shared(new Test());
collector_Test.insert(self);
out[0] = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL);
*reinterpret_cast<Shared**> (mxGetData(out[0])) = self;
}
void Test_constructor_19(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
mexAtExit(&_deleteAllObjects);
using namespace geometry;
typedef boost::shared_ptr<Test> Shared;
double a = unwrap< double >(in[0]);
Matrix b = unwrap< Matrix >(in[1]);
Shared *self = new Shared(new Test(a,b));
collector_Test.insert(self);
out[0] = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL);
*reinterpret_cast<Shared**> (mxGetData(out[0])) = self;
}
void Test_deconstructor_20(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
using namespace geometry;
typedef boost::shared_ptr<Test> Shared;
checkArguments("delete_Test",nargout,nargin,1);
Shared *self = *reinterpret_cast<Shared**>(mxGetData(in[0]));
Collector_Test::iterator item;
item = collector_Test.find(self);
if(item != collector_Test.end()) {
delete self;
collector_Test.erase(item);
}
}
void Test_arg_EigenConstRef_21(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
using namespace geometry;
typedef boost::shared_ptr<Test> Shared;
checkArguments("arg_EigenConstRef",nargout,nargin-1,1);
Shared obj = unwrap_shared_ptr<Test>(in[0], "Test");
Matrix& value = *unwrap_shared_ptr< Matrix >(in[1], "Matrix");
obj->arg_EigenConstRef(value);
}
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> Shared;
checkArguments("create_MixedPtrs",nargout,nargin-1,0);
Shared obj = unwrap_shared_ptr<Test>(in[0], "Test");
pair< Test, SharedTest > result = obj->create_MixedPtrs();
SharedTest* ret = new SharedTest(new Test(result.first));
out[0] = wrap_shared_ptr(ret,"Test");
SharedTest* ret = new SharedTest(result.second);
out[1] = wrap_shared_ptr(ret,"Test");
}
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> Shared;
checkArguments("create_ptrs",nargout,nargin-1,0);
Shared obj = unwrap_shared_ptr<Test>(in[0], "Test");
pair< SharedTest, SharedTest > result = obj->create_ptrs();
SharedTest* ret = new SharedTest(result.first);
out[0] = wrap_shared_ptr(ret,"Test");
SharedTest* ret = new SharedTest(result.second);
out[1] = wrap_shared_ptr(ret,"Test");
}
void Test_print_24(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
using namespace geometry;
typedef boost::shared_ptr<Test> Shared;
checkArguments("print",nargout,nargin-1,0);
Shared obj = unwrap_shared_ptr<Test>(in[0], "Test");
obj->print();
}
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<Test> Shared;
checkArguments("return_Point2Ptr",nargout,nargin-1,1);
Shared obj = unwrap_shared_ptr<Test>(in[0], "Test");
bool value = unwrap< bool >(in[1]);
SharedPoint2 result = obj->return_Point2Ptr(value);
SharedPoint2* ret = new SharedPoint2(result);
out[0] = wrap_shared_ptr(ret,"Point2");
}
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> Shared;
checkArguments("return_Test",nargout,nargin-1,1);
Shared obj = unwrap_shared_ptr<Test>(in[0], "Test");
boost::shared_ptr<Test> value = unwrap_shared_ptr< Test >(in[1], "Test");
Test result = obj->return_Test(value);
SharedTest* ret = new SharedTest(new Test(result));
out[0] = wrap_shared_ptr(ret,"Test");
}
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> Shared;
checkArguments("return_TestPtr",nargout,nargin-1,1);
Shared obj = unwrap_shared_ptr<Test>(in[0], "Test");
boost::shared_ptr<Test> value = unwrap_shared_ptr< Test >(in[1], "Test");
SharedTest result = obj->return_TestPtr(value);
SharedTest* ret = new SharedTest(result);
out[0] = wrap_shared_ptr(ret,"Test");
}
void Test_return_bool_28(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
using namespace geometry;
typedef boost::shared_ptr<Test> Shared;
checkArguments("return_bool",nargout,nargin-1,1);
Shared obj = unwrap_shared_ptr<Test>(in[0], "Test");
bool value = unwrap< bool >(in[1]);
bool result = obj->return_bool(value);
out[0] = wrap< bool >(result);
}
void Test_return_double_29(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
using namespace geometry;
typedef boost::shared_ptr<Test> Shared;
checkArguments("return_double",nargout,nargin-1,1);
Shared obj = unwrap_shared_ptr<Test>(in[0], "Test");
double value = unwrap< double >(in[1]);
double result = obj->return_double(value);
out[0] = wrap< double >(result);
}
void Test_return_field_30(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
using namespace geometry;
typedef boost::shared_ptr<Test> Shared;
checkArguments("return_field",nargout,nargin-1,1);
Shared obj = unwrap_shared_ptr<Test>(in[0], "Test");
Test& t = *unwrap_shared_ptr< Test >(in[1], "Test");
bool result = obj->return_field(t);
out[0] = wrap< bool >(result);
}
void Test_return_int_31(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
using namespace geometry;
typedef boost::shared_ptr<Test> Shared;
checkArguments("return_int",nargout,nargin-1,1);
Shared obj = unwrap_shared_ptr<Test>(in[0], "Test");
int value = unwrap< int >(in[1]);
int result = obj->return_int(value);
out[0] = wrap< int >(result);
}
void Test_return_matrix1_32(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
using namespace geometry;
typedef boost::shared_ptr<Test> Shared;
checkArguments("return_matrix1",nargout,nargin-1,1);
Shared obj = unwrap_shared_ptr<Test>(in[0], "Test");
Matrix value = unwrap< Matrix >(in[1]);
Matrix result = obj->return_matrix1(value);
out[0] = wrap< Matrix >(result);
}
void Test_return_matrix2_33(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
using namespace geometry;
typedef boost::shared_ptr<Test> Shared;
checkArguments("return_matrix2",nargout,nargin-1,1);
Shared obj = unwrap_shared_ptr<Test>(in[0], "Test");
Matrix value = unwrap< Matrix >(in[1]);
Matrix result = obj->return_matrix2(value);
out[0] = wrap< Matrix >(result);
}
void Test_return_pair_34(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
using namespace geometry;
typedef boost::shared_ptr<Test> Shared;
checkArguments("return_pair",nargout,nargin-1,2);
Shared obj = unwrap_shared_ptr<Test>(in[0], "Test");
Vector v = unwrap< Vector >(in[1]);
Matrix A = unwrap< Matrix >(in[2]);
pair< Vector, Matrix > result = obj->return_pair(v,A);
out[0] = wrap< Vector >(result.first);
out[1] = wrap< Matrix >(result.second);
}
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> Shared;
checkArguments("return_ptrs",nargout,nargin-1,2);
Shared obj = unwrap_shared_ptr<Test>(in[0], "Test");
boost::shared_ptr<Test> p1 = unwrap_shared_ptr< Test >(in[1], "Test");
boost::shared_ptr<Test> p2 = unwrap_shared_ptr< Test >(in[2], "Test");
pair< SharedTest, SharedTest > result = obj->return_ptrs(p1,p2);
SharedTest* ret = new SharedTest(result.first);
out[0] = wrap_shared_ptr(ret,"Test");
SharedTest* ret = new SharedTest(result.second);
out[1] = wrap_shared_ptr(ret,"Test");
}
void Test_return_size_t_36(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
using namespace geometry;
typedef boost::shared_ptr<Test> Shared;
checkArguments("return_size_t",nargout,nargin-1,1);
Shared obj = unwrap_shared_ptr<Test>(in[0], "Test");
size_t value = unwrap< size_t >(in[1]);
size_t result = obj->return_size_t(value);
out[0] = wrap< size_t >(result);
}
void Test_return_string_37(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
using namespace geometry;
typedef boost::shared_ptr<Test> Shared;
checkArguments("return_string",nargout,nargin-1,1);
Shared obj = unwrap_shared_ptr<Test>(in[0], "Test");
string value = unwrap< string >(in[1]);
string result = obj->return_string(value);
out[0] = wrap< string >(result);
}
void Test_return_vector1_38(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
using namespace geometry;
typedef boost::shared_ptr<Test> Shared;
checkArguments("return_vector1",nargout,nargin-1,1);
Shared obj = unwrap_shared_ptr<Test>(in[0], "Test");
Vector value = unwrap< Vector >(in[1]);
Vector result = obj->return_vector1(value);
out[0] = wrap< Vector >(result);
}
void Test_return_vector2_39(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
using namespace geometry;
typedef boost::shared_ptr<Test> Shared;
checkArguments("return_vector2",nargout,nargin-1,1);
Shared obj = unwrap_shared_ptr<Test>(in[0], "Test");
Vector value = unwrap< Vector >(in[1]);
Vector result = obj->return_vector2(value);
out[0] = wrap< Vector >(result);
}
void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
mstream mout;
std::streambuf *outbuf = std::cout.rdbuf(&mout);
int id = unwrap<int>(in[0]);
switch(id) {
case 0:
Point2_constructor_0(nargout, out, nargin-1, in+1);
break;
case 1:
Point2_constructor_1(nargout, out, nargin-1, in+1);
break;
case 2:
Point2_constructor_2(nargout, out, nargin-1, in+1);
break;
case 3:
Point2_deconstructor_3(nargout, out, nargin-1, in+1);
break;
case 4:
Point2_argChar_4(nargout, out, nargin-1, in+1);
break;
case 5:
Point2_argUChar_5(nargout, out, nargin-1, in+1);
break;
case 6:
Point2_dim_6(nargout, out, nargin-1, in+1);
break;
case 7:
Point2_returnChar_7(nargout, out, nargin-1, in+1);
break;
case 8:
Point2_vectorConfusion_8(nargout, out, nargin-1, in+1);
break;
case 9:
Point2_x_9(nargout, out, nargin-1, in+1);
break;
case 10:
Point2_y_10(nargout, out, nargin-1, in+1);
break;
case 11:
Point3_constructor_11(nargout, out, nargin-1, in+1);
break;
case 12:
Point3_constructor_12(nargout, out, nargin-1, in+1);
break;
case 13:
Point3_deconstructor_13(nargout, out, nargin-1, in+1);
break;
case 14:
Point3_norm_14(nargout, out, nargin-1, in+1);
break;
case 15:
Point3_StaticFunctionRet_15(nargout, out, nargin-1, in+1);
break;
case 16:
Point3_staticFunction_16(nargout, out, nargin-1, in+1);
break;
case 17:
Test_constructor_17(nargout, out, nargin-1, in+1);
break;
case 18:
Test_constructor_18(nargout, out, nargin-1, in+1);
break;
case 19:
Test_constructor_19(nargout, out, nargin-1, in+1);
break;
case 20:
Test_deconstructor_20(nargout, out, nargin-1, in+1);
break;
case 21:
Test_arg_EigenConstRef_21(nargout, out, nargin-1, in+1);
break;
case 22:
Test_create_MixedPtrs_22(nargout, out, nargin-1, in+1);
break;
case 23:
Test_create_ptrs_23(nargout, out, nargin-1, in+1);
break;
case 24:
Test_print_24(nargout, out, nargin-1, in+1);
break;
case 25:
Test_return_Point2Ptr_25(nargout, out, nargin-1, in+1);
break;
case 26:
Test_return_Test_26(nargout, out, nargin-1, in+1);
break;
case 27:
Test_return_TestPtr_27(nargout, out, nargin-1, in+1);
break;
case 28:
Test_return_bool_28(nargout, out, nargin-1, in+1);
break;
case 29:
Test_return_double_29(nargout, out, nargin-1, in+1);
break;
case 30:
Test_return_field_30(nargout, out, nargin-1, in+1);
break;
case 31:
Test_return_int_31(nargout, out, nargin-1, in+1);
break;
case 32:
Test_return_matrix1_32(nargout, out, nargin-1, in+1);
break;
case 33:
Test_return_matrix2_33(nargout, out, nargin-1, in+1);
break;
case 34:
Test_return_pair_34(nargout, out, nargin-1, in+1);
break;
case 35:
Test_return_ptrs_35(nargout, out, nargin-1, in+1);
break;
case 36:
Test_return_size_t_36(nargout, out, nargin-1, in+1);
break;
case 37:
Test_return_string_37(nargout, out, nargin-1, in+1);
break;
case 38:
Test_return_vector1_38(nargout, out, nargin-1, in+1);
break;
case 39:
Test_return_vector2_39(nargout, out, nargin-1, in+1);
break;
}
std::cout.rdbuf(outbuf);
}

View File

@ -1,59 +0,0 @@
% automatically generated by wrap
echo on
toolboxpath = mfilename('fullpath');
delims = find(toolboxpath == '/' | toolboxpath == '\');
toolboxpath = toolboxpath(1:(delims(end)-1));
clear delims
addpath(toolboxpath);
%% Point2
cd(toolboxpath)
mex -O5 new_Point2.cpp
cd @Point2
mex -O5 x.cpp
mex -O5 y.cpp
mex -O5 dim.cpp
mex -O5 returnChar.cpp
mex -O5 argChar.cpp
mex -O5 argUChar.cpp
mex -O5 vectorConfusion.cpp
%% Point3
cd(toolboxpath)
mex -O5 new_Point3.cpp
mex -O5 Point3_staticFunction.cpp
mex -O5 Point3_StaticFunctionRet.cpp
cd @Point3
mex -O5 norm.cpp
%% Test
cd(toolboxpath)
mex -O5 new_Test.cpp
cd @Test
mex -O5 return_pair.cpp
mex -O5 return_bool.cpp
mex -O5 return_size_t.cpp
mex -O5 return_int.cpp
mex -O5 return_double.cpp
mex -O5 return_string.cpp
mex -O5 return_vector1.cpp
mex -O5 return_matrix1.cpp
mex -O5 return_vector2.cpp
mex -O5 return_matrix2.cpp
mex -O5 arg_EigenConstRef.cpp
mex -O5 return_field.cpp
mex -O5 return_TestPtr.cpp
mex -O5 return_Test.cpp
mex -O5 return_Point2Ptr.cpp
mex -O5 create_ptrs.cpp
mex -O5 create_MixedPtrs.cpp
mex -O5 return_ptrs.cpp
mex -O5 print.cpp
cd(toolboxpath)
echo off

View File

@ -1,41 +0,0 @@
// automatically generated by wrap
#include <wrap/matlab.h>
#include <Point2.h>
typedef boost::shared_ptr<Point2> Shared;
static std::set<Shared*> collector;
void cleanup(void) {
for(std::set<Shared*>::iterator iter = collector.begin(); iter != collector.end(); ) {
delete *iter;
collector.erase(iter++);
}
}
void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
mexAtExit(cleanup);
const mxArray* input = in[0];
Shared* self = *(Shared**) mxGetData(input);
if(self) {
if(nargin > 1) {
collector.insert(self);
}
else if(collector.erase(self))
delete self;
} else {
int nc = unwrap<int>(in[1]);
if(nc == 0)
self = new Shared(new Point2());
if(nc == 1) {
double x = unwrap< double >(in[2]);
double y = unwrap< double >(in[3]);
self = new Shared(new Point2(x,y));
}
collector.insert(self);
out[0] = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL);
*reinterpret_cast<Shared**> (mxGetPr(out[0])) = self;
}
}

View File

@ -1,4 +0,0 @@
% automatically generated by wrap
function result = new_Point2(obj,x,y)
error('need to compile new_Point2.cpp');
end

Some files were not shown because too many files have changed in this diff Show More