Added static function parsing to wrap, included Expmap/Logmap in geometric objects. Static functions appear to still crash matlab, however.

release/4.3a0
Alex Cunningham 2011-12-02 02:32:18 +00:00
parent eb109c4dc5
commit 221a6ad877
73 changed files with 432 additions and 154 deletions

15
gtsam.h
View File

@ -8,14 +8,17 @@
* Constructors must appear in a class before any methods
* Methods can only return Matrix, Vector, double, int, void, and a shared_ptr to any other object
* Comments can use either C++ or C style
* Static methods are not supported
* Static methods are not supported - FIXED
* Methods must start with a lowercase letter
* Static methods must start with an uppercase letter
* Classes must start with an uppercase letter
*/
class Point2 {
Point2();
Point2(double x, double y);
static Point2* Expmap_(Vector v);
static Vector Logmap(const Point2& p);
void print(string s) const;
double x();
double y();
@ -29,6 +32,8 @@ class Point3 {
Point3();
Point3(double x, double y, double z);
Point3(Vector v);
static Point3* Expmap_(Vector v);
static Vector Logmap(const Point3& p);
void print(string s) const;
bool equals(const Point3& p, double tol);
Vector vector() const;
@ -44,6 +49,8 @@ class Point3 {
class Rot2 {
Rot2();
Rot2(double theta);
static Rot2* Expmap_(Vector v);
static Vector Logmap(const Rot2& p);
void print(string s) const;
bool equals(const Rot2& rot, double tol) const;
double c() const;
@ -57,6 +64,8 @@ class Rot2 {
class Rot3 {
Rot3();
Rot3(Matrix R);
static Rot3* Expmap_(Vector v);
static Vector Logmap(const Rot3& p);
Matrix matrix() const;
Matrix transpose() const;
Vector xyz() const;
@ -75,6 +84,8 @@ class Pose2 {
Pose2(double theta, const Point2& t);
Pose2(const Rot2& r, const Point2& t);
Pose2(Vector v);
static Pose2* Expmap_(Vector v);
static Vector Logmap(const Pose2& p);
void print(string s) const;
bool equals(const Pose2& pose, double tol) const;
double x() const;
@ -92,6 +103,8 @@ class Pose3 {
Pose3(const Rot3& r, const Point3& t);
Pose3(Vector v);
Pose3(Matrix t);
static Pose3* Expmap_(Vector v);
static Vector Logmap(const Pose3& p);
void print(string s) const;
bool equals(const Pose3& pose, double tol) const;
double x() const;

View File

@ -111,6 +111,9 @@ public:
/// Exponential map around identity - just create a Point2 from a vector
static inline Point2 Expmap(const Vector& v) { return Point2(v); }
static inline boost::shared_ptr<Point2> Expmap_(const Vector& v) {
return boost::shared_ptr<Point2>(new Point2(Expmap(v)));
}
/// Log map around identity - just return the Point2 as a vector
static inline Vector Logmap(const Point2& dp) { return Vector_(2, dp.x(), dp.y()); }

View File

@ -108,6 +108,9 @@ namespace gtsam {
/** Exponential map at identity - just create a Point3 from x,y,z */
static inline Point3 Expmap(const Vector& v) { return Point3(v); }
static inline boost::shared_ptr<Point3> Expmap_(const Vector& v) {
return boost::shared_ptr<Point3>(new Point3(Expmap(v)));
}
/** Log map at identity - return the x,y,z of this point */
static inline Vector Logmap(const Point3& dp) { return Vector_(3, dp.x(), dp.y(), dp.z()); }

View File

@ -140,6 +140,9 @@ public:
/// Exponential map from Lie algebra se(2) to SE(2)
static Pose2 Expmap(const Vector& xi);
static inline boost::shared_ptr<Pose2> Expmap_(const Vector& v) {
return boost::shared_ptr<Pose2>(new Pose2(Expmap(v)));
}
/// Exponential map from SE(2) to Lie algebra se(2)
static Vector Logmap(const Pose2& p);

View File

@ -134,6 +134,9 @@ namespace gtsam {
/// Exponential map from Lie algebra se(3) to SE(3)
static Pose3 Expmap(const Vector& xi);
static inline boost::shared_ptr<Pose3> Expmap_(const Vector& v) {
return boost::shared_ptr<Pose3>(new Pose3(Expmap(v)));
}
/// Exponential map from SE(3) to Lie algebra se(3)
static Vector Logmap(const Pose3& p);

View File

@ -189,6 +189,9 @@ namespace gtsam {
else
return Rot2::fromAngle(v(0));
}
static inline boost::shared_ptr<Rot2> Expmap_(const Vector& v) {
return boost::shared_ptr<Rot2>(new Rot2(Expmap(v)));
}
/// Logmap around identity - return the angle of the rotation
static inline Vector Logmap(const Rot2& r) {

View File

@ -202,6 +202,9 @@ namespace gtsam {
if(zero(v)) return Rot3M();
else return rodriguez(v);
}
static inline boost::shared_ptr<Rot3M> Expmap_(const Vector& v) {
return boost::shared_ptr<Rot3M>(new Rot3M(Expmap(v)));
}
/**
* Log map at identity - return the canonical coordinates of this rotation

View File

@ -67,6 +67,14 @@ void Class::matlab_methods(const string& classPath, const string& nameSpace) {
}
}
/* ************************************************************************* */
void Class::matlab_static_methods(const string& toolboxPath, const string& nameSpace) {
BOOST_FOREACH(StaticMethod& m, static_methods) {
m.matlab_mfile (toolboxPath, name);
m.matlab_wrapper(toolboxPath, name, nameSpace);
}
}
/* ************************************************************************* */
void Class::matlab_make_fragment(ofstream& ofs,
const string& toolboxPath,
@ -75,6 +83,8 @@ void Class::matlab_make_fragment(ofstream& ofs,
string mex = "mex " + mexFlags + " ";
BOOST_FOREACH(Constructor c, constructors)
ofs << mex << c.matlab_wrapper_name(name) << ".cpp" << endl;
BOOST_FOREACH(StaticMethod sm, static_methods)
ofs << mex << name + "_" + sm.name_ << ".cpp" << endl;
ofs << endl << "cd @" << name << endl;
BOOST_FOREACH(Method m, methods)
ofs << mex << m.name_ << ".cpp" << endl;

View File

@ -22,6 +22,7 @@
#include "Constructor.h"
#include "Method.h"
#include "StaticMethod.h"
/// Class has name, constructors, methods
struct Class {
@ -29,10 +30,11 @@ struct Class {
Class(bool verbose=true) : verbose_(verbose) {}
// Then the instance variables are set directly by the Module constructor
std::string name; ///< Class name
std::list<Constructor> constructors; ///< Class constructors
std::list<Method> methods; ///< Class methods
bool verbose_; ///< verbose flag
std::string name; ///< Class name
std::list<Constructor> constructors; ///< Class constructors
std::list<Method> methods; ///< Class methods
std::list<StaticMethod> static_methods; ///< Static methods
bool verbose_; ///< verbose flag
// And finally MATLAB code is emitted, methods below called by Module::matlab_code
void matlab_proxy(const std::string& classFile); ///< emit proxy class
@ -40,6 +42,8 @@ struct Class {
const std::string& nameSpace); ///< emit constructor wrappers
void matlab_methods(const std::string& classPath,
const std::string& nameSpace); ///< emit method wrappers
void matlab_static_methods(const std::string& classPath,
const std::string& nameSpace); ///< emit static method wrappers
void matlab_make_fragment(std::ofstream& ofs,
const std::string& toolboxPath,
const std::string& mexFlags); ///< emit make fragment for global make script

View File

@ -15,7 +15,7 @@ check_PROGRAMS =
if ENABLE_BUILD_TOOLBOX
# Build a library from the core sources
sources += utilities.cpp Argument.cpp Constructor.cpp Method.cpp Class.cpp Module.cpp
sources += utilities.cpp Argument.cpp ReturnValue.cpp Constructor.cpp Method.cpp StaticMethod.cpp Class.cpp Module.cpp
check_PROGRAMS += tests/testSpirit tests/testWrap
noinst_PROGRAMS = wrap

View File

@ -24,27 +24,6 @@
using namespace std;
/* ************************************************************************* */
// auxiliary function to wrap an argument into a shared_ptr template
/* ************************************************************************* */
string maybe_shared_ptr(bool add, const string& type) {
string str = add? "shared_ptr<" : "";
str += type;
if (add) str += ">";
return str;
}
/* ************************************************************************* */
string Method::return_type(bool add_ptr, pairing p) {
if (p==pair && returns_pair_) {
string str = "pair< " +
maybe_shared_ptr(add_ptr && returns_ptr_, returns_) + ", " +
maybe_shared_ptr(add_ptr && returns_ptr_, returns2_) + " >";
return str;
} else
return maybe_shared_ptr(add_ptr && returns_ptr_, (p==arg2)? returns2_ : returns_);
}
/* ************************************************************************* */
void Method::matlab_mfile(const string& classPath) {
@ -55,7 +34,7 @@ void Method::matlab_mfile(const string& classPath) {
if(verbose_) cerr << "generating " << wrapperFile << endl;
// generate code
string returnType = returns_pair_? "[first,second]" : "result";
string returnType = returnVal_.matlab_returnType();
ofs << "function " << returnType << " = " << name_ << "(obj";
if (args_.size()) ofs << "," << args_.names();
ofs << ")" << endl;
@ -98,7 +77,7 @@ void Method::matlab_wrapper(const string& classPath,
// get class pointer
// example: shared_ptr<Test> = unwrap_shared_ptr< Test >(in[0], "Test");
ofs << " shared_ptr<" << className << "> self = unwrap_shared_ptr< " << className
ofs << " shared_ptr<" << ((is_const_) ? "const " : "") << className << "> self = unwrap_shared_ptr< " << className
<< " >(in[0],\"" << className << "\");" << endl;
// unwrap arguments, see Argument.cpp
@ -107,26 +86,13 @@ void Method::matlab_wrapper(const string& classPath,
// call method
// example: bool result = self->return_field(t);
ofs << " ";
if (returns_!="void")
ofs << return_type(true,pair) << " result = ";
if (returnVal_.returns_!="void")
ofs << returnVal_.return_type(true,ReturnValue::pair) << " result = ";
ofs << "self->" << name_ << "(" << args_.names() << ");\n";
// wrap result
// example: out[0]=wrap<bool>(result);
if (returns_pair_) {
if (returns_ptr_)
ofs << " out[0] = wrap_shared_ptr(result.first,\"" << returns_ << "\");\n";
else
ofs << " out[0] = wrap< " << return_type(true,arg1) << " >(result.first);\n";
if (returns_ptr2_)
ofs << " out[1] = wrap_shared_ptr(result.second,\"" << returns2_ << "\");\n";
else
ofs << " out[1] = wrap< " << return_type(true,arg2) << " >(result.second);\n";
}
else if (returns_ptr_)
ofs << " out[0] = wrap_shared_ptr(result,\"" << returns_ << "\");\n";
else if (returns_!="void")
ofs << " out[0] = wrap< " << return_type(true,arg1) << " >(result);\n";
returnVal_.wrap_result(ofs);
// finish
ofs << "}\n";

View File

@ -21,27 +21,23 @@
#include <list>
#include "Argument.h"
#include "ReturnValue.h"
/// Method class
struct Method {
/// Constructor creates empty object
Method(bool verbose = true) :
returns_ptr_(false), returns_ptr2_(false), returns_pair_(false), verbose_(
verbose) {
}
verbose_(verbose) {}
// Then the instance variables are set directly by the Module constructor
bool is_const_;
ArgumentList args_;
std::string returns_, returns2_, name_;
bool returns_ptr_, returns_ptr2_, returns_pair_;
bool verbose_;
bool is_const_;
std::string name_;
ArgumentList args_;
ReturnValue returnVal_;
enum pairing {
arg1, arg2, pair
};
std::string return_type(bool add_ptr, pairing p);
// std::string return_type(bool add_ptr, pairing p);
// MATLAB code generation
// classPath is class directory, e.g., ../matlab/@Point2

View File

@ -43,10 +43,12 @@ Module::Module(const string& interfacePath,
{
// these variables will be imperatively updated to gradually build [cls]
// The one with postfix 0 are used to reset the variables after parse.
ReturnValue retVal0, retVal;
Argument arg0, arg;
ArgumentList args0, args;
Constructor constructor0(verbose), constructor(verbose);
Method method0(verbose), method(verbose);
StaticMethod static_method0(verbose), static_method(verbose);
Class cls0(verbose),cls(verbose);
//----------------------------------------------------------------------------
@ -100,20 +102,20 @@ Module::Module(const string& interfacePath,
[assign_a(constructor,constructor0)];
Rule returnType1_p =
basisType_p[assign_a(method.returns_)] |
((className_p | "Vector" | "Matrix")[assign_a(method.returns_)] >>
!ch_p('*') [assign_a(method.returns_ptr_,true)]);
basisType_p[assign_a(retVal.returns_)] |
((className_p | "Vector" | "Matrix")[assign_a(retVal.returns_)] >>
!ch_p('*') [assign_a(retVal.returns_ptr_,true)]);
Rule returnType2_p =
basisType_p[assign_a(method.returns2_)] |
((className_p | "Vector" | "Matrix")[assign_a(method.returns2_)] >>
!ch_p('*') [assign_a(method.returns_ptr2_,true)]);
basisType_p[assign_a(retVal.returns2_)] |
((className_p | "Vector" | "Matrix")[assign_a(retVal.returns2_)] >>
!ch_p('*') [assign_a(retVal.returns_ptr2_,true)]);
Rule pair_p =
(str_p("pair") >> '<' >> returnType1_p >> ',' >> returnType2_p >> '>')
[assign_a(method.returns_pair_,true)];
[assign_a(retVal.returns_pair_,true)];
Rule void_p = str_p("void")[assign_a(method.returns_)];
Rule void_p = str_p("void")[assign_a(retVal.returns_)];
Rule returnType_p = void_p | returnType1_p | pair_p;
@ -125,14 +127,30 @@ Module::Module(const string& interfacePath,
!str_p("const")[assign_a(method.is_const_,true)] >> ';' >> *comments_p)
[assign_a(method.args_,args)]
[assign_a(args,args0)]
[assign_a(method.returnVal_,retVal)]
[assign_a(retVal,retVal0)]
[push_back_a(cls.methods, method)]
[assign_a(method,method0)];
Rule staticMethodName_p = lexeme_d[upper_p >> *(alnum_p | '_')];
Rule static_method_p =
(str_p("static") >> returnType_p >> staticMethodName_p[assign_a(static_method.name_)] >>
'(' >> argumentList_p >> ')' >> ';' >> *comments_p)
[assign_a(static_method.args_,args)]
[assign_a(args,args0)]
[assign_a(static_method.returnVal_,retVal)]
[assign_a(retVal,retVal0)]
[push_back_a(cls.static_methods, static_method)]
[assign_a(static_method,static_method0)];
Rule methods_p = method_p | static_method_p;
Rule class_p = str_p("class") >> className_p[assign_a(cls.name)] >> '{' >>
*comments_p >>
*constructor_p >>
*comments_p >>
*method_p >>
*methods_p >>
*comments_p >>
'}' >> ";";
@ -214,6 +232,7 @@ void Module::matlab_code(const string& toolboxPath,
// create constructor and method wrappers
cls.matlab_constructors(toolboxPath,nameSpace);
cls.matlab_static_methods(toolboxPath,nameSpace);
cls.matlab_methods(classPath,nameSpace);
// add lines to make m-file

View File

@ -17,10 +17,10 @@ OBJECT CREATION
new_GaussianFactorGraph_ calls wrap_constructed in matlab.h, see documentation there
METHOD (AND CONSTRUCTOR) ARGUMENTS
- simple argument types of methods, such as "double", will be converted in the
- Simple argument types of methods, such as "double", will be converted in the
mex warppers by calling unwrap<double>, defined in matlab.h
- Vector and Matric arguments are normally passed by reference in GTSAM, but
in gtsam.h you need to pretedn they are passed by value, to trigger the
- Vector and Matrix arguments are normally passed by reference in GTSAM, but
in gtsam.h you need to pretend they are passed by value, to trigger the
generation of the correct conversion routines unwrap<Vector> and unwrap<Matrix>
- passing classes as arguments works, provided they are passed by reference.
This triggers a call to unwrap_shared_ptr

44
wrap/ReturnValue.cpp Normal file
View File

@ -0,0 +1,44 @@
/**
* @file ReturnValue.cpp
*
* @date Dec 1, 2011
* @author Alex Cunningham
*/
#include "ReturnValue.h"
#include "utilities.h"
using namespace std;
/* ************************************************************************* */
string ReturnValue::return_type(bool add_ptr, pairing p) {
if (p==pair && returns_pair_) {
string str = "pair< " +
maybe_shared_ptr(add_ptr && returns_ptr_, returns_) + ", " +
maybe_shared_ptr(add_ptr && returns_ptr_, returns2_) + " >";
return str;
} else
return maybe_shared_ptr(add_ptr && returns_ptr_, (p==arg2)? returns2_ : returns_);
}
/* ************************************************************************* */
void ReturnValue::wrap_result(std::ostream& ofs) {
if (returns_pair_) {
if (returns_ptr_)
ofs << " out[0] = wrap_shared_ptr(result.first,\"" << returns_ << "\");\n";
else
ofs << " out[0] = wrap< " << return_type(true,arg1) << " >(result.first);\n";
if (returns_ptr2_)
ofs << " out[1] = wrap_shared_ptr(result.second,\"" << returns2_ << "\");\n";
else
ofs << " out[1] = wrap< " << return_type(true,arg2) << " >(result.second);\n";
}
else if (returns_ptr_)
ofs << " out[0] = wrap_shared_ptr(result,\"" << returns_ << "\");\n";
else if (returns_!="void")
ofs << " out[0] = wrap< " << return_type(true,arg1) << " >(result);\n";
}
/* ************************************************************************* */

34
wrap/ReturnValue.h Normal file
View File

@ -0,0 +1,34 @@
/**
* @file ReturnValue.h
*
* @brief Encapsulates a return value from a method
*
* @date Dec 1, 2011
* @author Alex Cunningham
*/
#include <ostream>
#pragma once
struct ReturnValue {
ReturnValue(bool verbose = true)
: verbose_(verbose), returns_ptr_(false), returns_ptr2_(false), returns_pair_(false)
{}
bool verbose_;
std::string returns_, returns2_;
bool returns_ptr_, returns_ptr2_, returns_pair_;
typedef enum {
arg1, arg2, pair
} pairing;
std::string return_type(bool add_ptr, pairing p);
std::string matlab_returnType() const { return returns_pair_? "[first,second]" : "result"; }
void wrap_result(std::ostream& ofs);
};

100
wrap/StaticMethod.cpp Normal file
View File

@ -0,0 +1,100 @@
/* ----------------------------------------------------------------------------
* 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 Method.ccp
* @author Frank Dellaert
**/
#include <iostream>
#include <fstream>
#include <boost/foreach.hpp>
#include "StaticMethod.h"
#include "utilities.h"
using namespace std;
/* ************************************************************************* */
void StaticMethod::matlab_mfile(const string& toolboxPath, const string& className) {
// open destination m-file
string full_name = className + "_" + name_;
string wrapperFile = toolboxPath + "/" + full_name + ".m";
ofstream ofs(wrapperFile.c_str());
if(!ofs) throw CantOpenFile(wrapperFile);
if(verbose_) cerr << "generating " << wrapperFile << endl;
// generate code
string returnType = returnVal_.matlab_returnType();
ofs << "function " << returnType << " = " << full_name << "(";
if (args_.size()) ofs << "," << args_.names();
ofs << ")" << endl;
ofs << "% usage: obj." << full_name << "(" << args_.names() << ")" << endl;
ofs << " error('need to compile " << full_name << ".cpp');" << endl;
ofs << "end" << endl;
// close file
ofs.close();
}
/* ************************************************************************* */
void StaticMethod::matlab_wrapper(const string& toolboxPath,
const string& className, const string& nameSpace)
{
// open destination wrapperFile
string full_name = className + "_" + name_;
string wrapperFile = toolboxPath + "/" + full_name + ".cpp";
ofstream ofs(wrapperFile.c_str());
if(!ofs) throw CantOpenFile(wrapperFile);
if(verbose_) cerr << "generating " << wrapperFile << endl;
// generate code
// header
emit_header_comment(ofs, "//");
ofs << "#include <wrap/matlab.h>\n";
ofs << "#include <" << className << ".h>\n";
if (!nameSpace.empty()) ofs << "using namespace " << nameSpace << ";" << endl;
// call
ofs << "void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[])\n";
// start
ofs << "{\n";
// check arguments
// extra argument obj -> nargin-1 is passed !
// example: checkArguments("equals",nargout,nargin-1,2);
ofs << " checkArguments(\"" << full_name << "\",nargout,nargin," << args_.size() << ");\n";
// unwrap arguments, see Argument.cpp
args_.matlab_unwrap(ofs,1);
// call method
// example: bool result = Point2::return_field(t);
ofs << " ";
if (returnVal_.returns_!="void")
ofs << returnVal_.return_type(true,ReturnValue::pair) << " result = ";
ofs << className << "::" << name_ << "(" << args_.names() << ");\n";
// wrap result
// example: out[0]=wrap<bool>(result);
returnVal_.wrap_result(ofs);
// finish
ofs << "}\n";
// close file
ofs.close();
}
/* ************************************************************************* */

49
wrap/StaticMethod.h Normal file
View File

@ -0,0 +1,49 @@
/* ----------------------------------------------------------------------------
* 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 StaticMethod.h
* @brief describes and generates code for static methods
* @author Frank Dellaert
* @author Alex Cunningham
**/
#pragma once
#include <string>
#include <list>
#include "Argument.h"
#include "ReturnValue.h"
/// StaticMethod class
struct StaticMethod {
/// Constructor creates empty object
StaticMethod(bool verbose = true) :
verbose_(verbose) {}
// Then the instance variables are set directly by the Module constructor
bool verbose_;
std::string name_;
ArgumentList args_;
ReturnValue returnVal_;
// MATLAB code generation
// toolboxPath is the core toolbox directory, e.g., ../matlab
// NOTE: static functions are not inside the class, and
// are created with [ClassName]_[FunctionName]() format
void matlab_mfile(const std::string& toolboxPath, const std::string& className); ///< m-file
void matlab_wrapper(const std::string& toolboxPath,
const std::string& className, const std::string& nameSpace); ///< wrapper
};

View File

@ -3,14 +3,17 @@
class Point2 {
Point2();
Point2(double x, double y);
double x();
double y();
double x() const;
double y() const;
int dim() const;
};
class Point3 {
Point3(double x, double y, double z);
double norm() const;
// Testing: static functions - use static keyword and uppercase
static double StaticFunction();
};
// another comment
@ -20,33 +23,33 @@ class Test {
// another comment
Test();
bool return_bool (bool value); // comment after a line!
size_t return_size_t (size_t value);
int return_int (int value);
double return_double (double value);
bool return_bool (bool value) const; // comment after a line!
size_t return_size_t (size_t value) const;
int return_int (int value) const;
double return_double (double value) const;
// comments in the middle!
// (more) comments in the middle!
string return_string (string value);
Vector return_vector1(Vector value);
Matrix return_matrix1(Matrix value);
Vector return_vector2(Vector value);
Matrix return_matrix2(Matrix value);
string return_string (string value) const;
Vector return_vector1(Vector value) const;
Matrix return_matrix1(Matrix value) const;
Vector return_vector2(Vector value) const;
Matrix return_matrix2(Matrix value) const;
pair<Vector,Matrix> return_pair (Vector v, Matrix A);
pair<Vector,Matrix> return_pair (Vector v, Matrix A) const;
bool return_field(const Test& t) const;
Test* return_TestPtr(Test* value);
Test* return_TestPtr(Test* value) const;
Point2* return_Point2Ptr(bool value);
Point2* return_Point2Ptr(bool value) const;
pair<Test*,Test*> create_ptrs ();
pair<Test*,Test*> return_ptrs (Test* p1, Test* p2);
pair<Test*,Test*> create_ptrs () const;
pair<Test*,Test*> return_ptrs (Test* p1, Test* p2) const;
void print();
void print() const;
// comments at the end!

View File

@ -36,9 +36,6 @@ using namespace std;
using namespace boost; // not usual, but for conciseness of generated code
// start GTSAM Specifics /////////////////////////////////////////////////
//typedef gtsam::Vector Vector; // NOTE: outside of gtsam namespace
//typedef gtsam::Matrix Matrix;
// to make keys be constructed from strings:
#define GTSAM_MAGIC_KEY
// to enable Matrix and Vector constructor for SharedGaussian:

View File

@ -1,10 +1,10 @@
// automatically generated by wrap on 2011-Oct-31
// automatically generated by wrap on 2011-Dec-01
#include <wrap/matlab.h>
#include <Point2.h>
void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
checkArguments("dim",nargout,nargin-1,0);
shared_ptr<Point2> self = unwrap_shared_ptr< Point2 >(in[0],"Point2");
shared_ptr<const Point2> self = unwrap_shared_ptr< Point2 >(in[0],"Point2");
int result = self->dim();
out[0] = wrap< int >(result);
}

View File

@ -1,5 +1,4 @@
function result = dim(obj)
% usage: obj.dim()
% automatically generated by wrap on 2011-Oct-31
error('need to compile dim.cpp');
end

View File

@ -1,10 +1,10 @@
// automatically generated by wrap on 2011-Oct-31
// automatically generated by wrap on 2011-Dec-01
#include <wrap/matlab.h>
#include <Point2.h>
void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
checkArguments("x",nargout,nargin-1,0);
shared_ptr<Point2> self = unwrap_shared_ptr< Point2 >(in[0],"Point2");
shared_ptr<const Point2> self = unwrap_shared_ptr< Point2 >(in[0],"Point2");
double result = self->x();
out[0] = wrap< double >(result);
}

View File

@ -1,5 +1,4 @@
function result = x(obj)
% usage: obj.x()
% automatically generated by wrap on 2011-Oct-31
error('need to compile x.cpp');
end

View File

@ -1,10 +1,10 @@
// automatically generated by wrap on 2011-Oct-31
// automatically generated by wrap on 2011-Dec-01
#include <wrap/matlab.h>
#include <Point2.h>
void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
checkArguments("y",nargout,nargin-1,0);
shared_ptr<Point2> self = unwrap_shared_ptr< Point2 >(in[0],"Point2");
shared_ptr<const Point2> self = unwrap_shared_ptr< Point2 >(in[0],"Point2");
double result = self->y();
out[0] = wrap< double >(result);
}

View File

@ -1,5 +1,4 @@
function result = y(obj)
% usage: obj.y()
% automatically generated by wrap on 2011-Oct-31
error('need to compile y.cpp');
end

View File

@ -1,10 +1,10 @@
// automatically generated by wrap on 2011-Oct-31
// automatically generated by wrap on 2011-Dec-01
#include <wrap/matlab.h>
#include <Point3.h>
void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
checkArguments("norm",nargout,nargin-1,0);
shared_ptr<Point3> self = unwrap_shared_ptr< Point3 >(in[0],"Point3");
shared_ptr<const Point3> self = unwrap_shared_ptr< Point3 >(in[0],"Point3");
double result = self->norm();
out[0] = wrap< double >(result);
}

View File

@ -1,10 +1,10 @@
// automatically generated by wrap on 2011-Oct-31
// automatically generated by wrap on 2011-Dec-01
#include <wrap/matlab.h>
#include <Test.h>
void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
checkArguments("create_ptrs",nargout,nargin-1,0);
shared_ptr<Test> self = unwrap_shared_ptr< Test >(in[0],"Test");
shared_ptr<const Test> self = unwrap_shared_ptr< Test >(in[0],"Test");
pair< shared_ptr<Test>, shared_ptr<Test> > result = self->create_ptrs();
out[0] = wrap_shared_ptr(result.first,"Test");
out[1] = wrap_shared_ptr(result.second,"Test");

View File

@ -1,5 +1,4 @@
function [first,second] = create_ptrs(obj)
% usage: obj.create_ptrs()
% automatically generated by wrap on 2011-Oct-31
error('need to compile create_ptrs.cpp');
end

View File

@ -1,9 +1,9 @@
// automatically generated by wrap on 2011-Oct-31
// automatically generated by wrap on 2011-Dec-01
#include <wrap/matlab.h>
#include <Test.h>
void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
checkArguments("print",nargout,nargin-1,0);
shared_ptr<Test> self = unwrap_shared_ptr< Test >(in[0],"Test");
shared_ptr<const Test> self = unwrap_shared_ptr< Test >(in[0],"Test");
self->print();
}

View File

@ -4,7 +4,7 @@
void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
checkArguments("return_Point2Ptr",nargout,nargin-1,1);
shared_ptr<Test> self = unwrap_shared_ptr< Test >(in[0],"Test");
shared_ptr<const Test> self = unwrap_shared_ptr< Test >(in[0],"Test");
bool value = unwrap< bool >(in[1]);
shared_ptr<Point2> result = self->return_Point2Ptr(value);
out[0] = wrap_shared_ptr(result,"Point2");

View File

@ -1,10 +1,10 @@
// automatically generated by wrap on 2011-Oct-31
// automatically generated by wrap on 2011-Dec-01
#include <wrap/matlab.h>
#include <Test.h>
void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
checkArguments("return_TestPtr",nargout,nargin-1,1);
shared_ptr<Test> self = unwrap_shared_ptr< Test >(in[0],"Test");
shared_ptr<const Test> self = unwrap_shared_ptr< Test >(in[0],"Test");
shared_ptr<Test> value = unwrap_shared_ptr< Test >(in[1], "Test");
shared_ptr<Test> result = self->return_TestPtr(value);
out[0] = wrap_shared_ptr(result,"Test");

View File

@ -1,5 +1,4 @@
function result = return_TestPtr(obj,value)
% usage: obj.return_TestPtr(value)
% automatically generated by wrap on 2011-Oct-31
error('need to compile return_TestPtr.cpp');
end

View File

@ -1,10 +1,10 @@
// automatically generated by wrap on 2011-Oct-31
// automatically generated by wrap on 2011-Dec-01
#include <wrap/matlab.h>
#include <Test.h>
void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
checkArguments("return_bool",nargout,nargin-1,1);
shared_ptr<Test> self = unwrap_shared_ptr< Test >(in[0],"Test");
shared_ptr<const Test> self = unwrap_shared_ptr< Test >(in[0],"Test");
bool value = unwrap< bool >(in[1]);
bool result = self->return_bool(value);
out[0] = wrap< bool >(result);

View File

@ -1,5 +1,4 @@
function result = return_bool(obj,value)
% usage: obj.return_bool(value)
% automatically generated by wrap on 2011-Oct-31
error('need to compile return_bool.cpp');
end

View File

@ -1,10 +1,10 @@
// automatically generated by wrap on 2011-Oct-31
// automatically generated by wrap on 2011-Dec-01
#include <wrap/matlab.h>
#include <Test.h>
void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
checkArguments("return_double",nargout,nargin-1,1);
shared_ptr<Test> self = unwrap_shared_ptr< Test >(in[0],"Test");
shared_ptr<const Test> self = unwrap_shared_ptr< Test >(in[0],"Test");
double value = unwrap< double >(in[1]);
double result = self->return_double(value);
out[0] = wrap< double >(result);

View File

@ -1,5 +1,4 @@
function result = return_double(obj,value)
% usage: obj.return_double(value)
% automatically generated by wrap on 2011-Oct-31
error('need to compile return_double.cpp');
end

View File

@ -1,10 +1,10 @@
// automatically generated by wrap on 2011-Oct-31
// automatically generated by wrap on 2011-Dec-01
#include <wrap/matlab.h>
#include <Test.h>
void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
checkArguments("return_field",nargout,nargin-1,1);
shared_ptr<Test> self = unwrap_shared_ptr< Test >(in[0],"Test");
shared_ptr<const Test> self = unwrap_shared_ptr< Test >(in[0],"Test");
Test& t = *unwrap_shared_ptr< Test >(in[1], "Test");
bool result = self->return_field(t);
out[0] = wrap< bool >(result);

View File

@ -1,5 +1,4 @@
function result = return_field(obj,t)
% usage: obj.return_field(t)
% automatically generated by wrap on 2011-Oct-31
error('need to compile return_field.cpp');
end

View File

@ -1,10 +1,10 @@
// automatically generated by wrap on 2011-Oct-31
// automatically generated by wrap on 2011-Dec-01
#include <wrap/matlab.h>
#include <Test.h>
void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
checkArguments("return_int",nargout,nargin-1,1);
shared_ptr<Test> self = unwrap_shared_ptr< Test >(in[0],"Test");
shared_ptr<const Test> self = unwrap_shared_ptr< Test >(in[0],"Test");
int value = unwrap< int >(in[1]);
int result = self->return_int(value);
out[0] = wrap< int >(result);

View File

@ -1,5 +1,4 @@
function result = return_int(obj,value)
% usage: obj.return_int(value)
% automatically generated by wrap on 2011-Oct-31
error('need to compile return_int.cpp');
end

View File

@ -1,10 +1,10 @@
// automatically generated by wrap on 2011-Oct-31
// automatically generated by wrap on 2011-Dec-01
#include <wrap/matlab.h>
#include <Test.h>
void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
checkArguments("return_matrix1",nargout,nargin-1,1);
shared_ptr<Test> self = unwrap_shared_ptr< Test >(in[0],"Test");
shared_ptr<const Test> self = unwrap_shared_ptr< Test >(in[0],"Test");
Matrix value = unwrap< Matrix >(in[1]);
Matrix result = self->return_matrix1(value);
out[0] = wrap< Matrix >(result);

View File

@ -1,5 +1,4 @@
function result = return_matrix1(obj,value)
% usage: obj.return_matrix1(value)
% automatically generated by wrap on 2011-Oct-31
error('need to compile return_matrix1.cpp');
end

View File

@ -1,10 +1,10 @@
// automatically generated by wrap on 2011-Oct-31
// automatically generated by wrap on 2011-Dec-01
#include <wrap/matlab.h>
#include <Test.h>
void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
checkArguments("return_matrix2",nargout,nargin-1,1);
shared_ptr<Test> self = unwrap_shared_ptr< Test >(in[0],"Test");
shared_ptr<const Test> self = unwrap_shared_ptr< Test >(in[0],"Test");
Matrix value = unwrap< Matrix >(in[1]);
Matrix result = self->return_matrix2(value);
out[0] = wrap< Matrix >(result);

View File

@ -1,5 +1,4 @@
function result = return_matrix2(obj,value)
% usage: obj.return_matrix2(value)
% automatically generated by wrap on 2011-Oct-31
error('need to compile return_matrix2.cpp');
end

View File

@ -1,10 +1,10 @@
// automatically generated by wrap on 2011-Oct-31
// automatically generated by wrap on 2011-Dec-01
#include <wrap/matlab.h>
#include <Test.h>
void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
checkArguments("return_pair",nargout,nargin-1,2);
shared_ptr<Test> self = unwrap_shared_ptr< Test >(in[0],"Test");
shared_ptr<const Test> self = unwrap_shared_ptr< Test >(in[0],"Test");
Vector v = unwrap< Vector >(in[1]);
Matrix A = unwrap< Matrix >(in[2]);
pair< Vector, Matrix > result = self->return_pair(v,A);

View File

@ -1,5 +1,4 @@
function [first,second] = return_pair(obj,v,A)
% usage: obj.return_pair(v,A)
% automatically generated by wrap on 2011-Oct-31
error('need to compile return_pair.cpp');
end

View File

@ -1,10 +1,10 @@
// automatically generated by wrap on 2011-Oct-31
// automatically generated by wrap on 2011-Dec-01
#include <wrap/matlab.h>
#include <Test.h>
void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
checkArguments("return_ptrs",nargout,nargin-1,2);
shared_ptr<Test> self = unwrap_shared_ptr< Test >(in[0],"Test");
shared_ptr<const Test> self = unwrap_shared_ptr< Test >(in[0],"Test");
shared_ptr<Test> p1 = unwrap_shared_ptr< Test >(in[1], "Test");
shared_ptr<Test> p2 = unwrap_shared_ptr< Test >(in[2], "Test");
pair< shared_ptr<Test>, shared_ptr<Test> > result = self->return_ptrs(p1,p2);

View File

@ -1,5 +1,4 @@
function [first,second] = return_ptrs(obj,p1,p2)
% usage: obj.return_ptrs(p1,p2)
% automatically generated by wrap on 2011-Oct-31
error('need to compile return_ptrs.cpp');
end

View File

@ -1,10 +1,10 @@
// automatically generated by wrap on 2011-Oct-31
// automatically generated by wrap on 2011-Dec-01
#include <wrap/matlab.h>
#include <Test.h>
void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
checkArguments("return_size_t",nargout,nargin-1,1);
shared_ptr<Test> self = unwrap_shared_ptr< Test >(in[0],"Test");
shared_ptr<const Test> self = unwrap_shared_ptr< Test >(in[0],"Test");
size_t value = unwrap< size_t >(in[1]);
size_t result = self->return_size_t(value);
out[0] = wrap< size_t >(result);

View File

@ -1,5 +1,4 @@
function result = return_size_t(obj,value)
% usage: obj.return_size_t(value)
% automatically generated by wrap on 2011-Oct-31
error('need to compile return_size_t.cpp');
end

View File

@ -1,10 +1,10 @@
// automatically generated by wrap on 2011-Oct-31
// automatically generated by wrap on 2011-Dec-01
#include <wrap/matlab.h>
#include <Test.h>
void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
checkArguments("return_string",nargout,nargin-1,1);
shared_ptr<Test> self = unwrap_shared_ptr< Test >(in[0],"Test");
shared_ptr<const Test> self = unwrap_shared_ptr< Test >(in[0],"Test");
string value = unwrap< string >(in[1]);
string result = self->return_string(value);
out[0] = wrap< string >(result);

View File

@ -1,5 +1,4 @@
function result = return_string(obj,value)
% usage: obj.return_string(value)
% automatically generated by wrap on 2011-Oct-31
error('need to compile return_string.cpp');
end

View File

@ -1,10 +1,10 @@
// automatically generated by wrap on 2011-Oct-31
// automatically generated by wrap on 2011-Dec-01
#include <wrap/matlab.h>
#include <Test.h>
void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
checkArguments("return_vector1",nargout,nargin-1,1);
shared_ptr<Test> self = unwrap_shared_ptr< Test >(in[0],"Test");
shared_ptr<const Test> self = unwrap_shared_ptr< Test >(in[0],"Test");
Vector value = unwrap< Vector >(in[1]);
Vector result = self->return_vector1(value);
out[0] = wrap< Vector >(result);

View File

@ -1,5 +1,4 @@
function result = return_vector1(obj,value)
% usage: obj.return_vector1(value)
% automatically generated by wrap on 2011-Oct-31
error('need to compile return_vector1.cpp');
end

View File

@ -1,10 +1,10 @@
// automatically generated by wrap on 2011-Oct-31
// automatically generated by wrap on 2011-Dec-01
#include <wrap/matlab.h>
#include <Test.h>
void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
checkArguments("return_vector2",nargout,nargin-1,1);
shared_ptr<Test> self = unwrap_shared_ptr< Test >(in[0],"Test");
shared_ptr<const Test> self = unwrap_shared_ptr< Test >(in[0],"Test");
Vector value = unwrap< Vector >(in[1]);
Vector result = self->return_vector2(value);
out[0] = wrap< Vector >(result);

View File

@ -1,5 +1,4 @@
function result = return_vector2(obj,value)
% usage: obj.return_vector2(value)
% automatically generated by wrap on 2011-Oct-31
error('need to compile return_vector2.cpp');
end

View File

@ -0,0 +1,9 @@
// automatically generated by wrap on 2011-Dec-01
#include <wrap/matlab.h>
#include <Point3.h>
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

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

View File

@ -1,4 +1,4 @@
% automatically generated by wrap on 2011-Nov-04
% automatically generated by wrap on 2011-Dec-01
echo on
toolboxpath = mfilename('fullpath');
@ -20,6 +20,7 @@ mex -O5 dim.cpp
%% Point3
cd(toolboxpath)
mex -O5 new_Point3_ddd.cpp
mex -O5 Point3_StaticFunction.cpp
cd @Point3
mex -O5 norm.cpp

View File

@ -1,4 +1,4 @@
// automatically generated by wrap on 2011-Oct-31
// automatically generated by wrap on 2011-Dec-01
#include <wrap/matlab.h>
#include <Point2.h>
void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[])

View File

@ -1,4 +1,4 @@
% automatically generated by wrap on 2011-Oct-31
% automatically generated by wrap on 2011-Dec-01
function result = new_Point2_(obj)
error('need to compile new_Point2_.cpp');
end

View File

@ -1,4 +1,4 @@
// automatically generated by wrap on 2011-Oct-31
// automatically generated by wrap on 2011-Dec-01
#include <wrap/matlab.h>
#include <Point2.h>
void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[])

View File

@ -1,4 +1,4 @@
% automatically generated by wrap on 2011-Oct-31
% automatically generated by wrap on 2011-Dec-01
function result = new_Point2_dd(obj,x,y)
error('need to compile new_Point2_dd.cpp');
end

View File

@ -1,4 +1,4 @@
// automatically generated by wrap on 2011-Oct-31
// automatically generated by wrap on 2011-Dec-01
#include <wrap/matlab.h>
#include <Point3.h>
void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[])

View File

@ -1,4 +1,4 @@
% automatically generated by wrap on 2011-Oct-31
% automatically generated by wrap on 2011-Dec-01
function result = new_Point3_ddd(obj,x,y,z)
error('need to compile new_Point3_ddd.cpp');
end

View File

@ -1,4 +1,4 @@
// automatically generated by wrap on 2011-Oct-31
// automatically generated by wrap on 2011-Dec-01
#include <wrap/matlab.h>
#include <Test.h>
void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[])

View File

@ -1,4 +1,4 @@
% automatically generated by wrap on 2011-Dec-01
function result = new_Test_(obj)
% automatically generated by wrap on 2011-Oct-31
error('need to compile new_Test_.cpp');
end

View File

@ -0,0 +1,10 @@
// automatically generated by wrap on 2011-Dec-01
#include <wrap/matlab.h>
#include <Test.h>
void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
checkArguments("new_Test_b",nargout,nargin,1);
bool value = unwrap< bool >(in[0]);
Test* self = new Test(value);
out[0] = wrap_constructed(self,"Test");
}

View File

@ -0,0 +1,4 @@
% automatically generated by wrap on 2011-Dec-01
function result = new_Test_b(obj,value)
error('need to compile new_Test_b.cpp');
end

View File

@ -61,6 +61,7 @@ TEST( wrap, parse ) {
EXPECT(cls.name=="Point3");
EXPECT(cls.constructors.size()==1);
EXPECT(cls.methods.size()==1);
EXPECT(cls.static_methods.size()==1);
// first constructor takes 3 doubles
Constructor c1 = cls.constructors.front();
@ -75,7 +76,7 @@ TEST( wrap, parse ) {
// check method
Method m1 = cls.methods.front();
EXPECT(m1.returns_=="double");
EXPECT(m1.returnVal_.returns_=="double");
EXPECT(m1.name_=="norm");
EXPECT(m1.args_.size()==0);
EXPECT(m1.is_const_);
@ -96,6 +97,8 @@ TEST( wrap, matlab_code ) {
EXPECT(files_equal(path + "/tests/expected/@Point3/Point3.m" , "actual/@Point3/Point3.m" ));
EXPECT(files_equal(path + "/tests/expected/new_Point3_ddd.m" , "actual/new_Point3_ddd.m" ));
EXPECT(files_equal(path + "/tests/expected/new_Point3_ddd.cpp", "actual/new_Point3_ddd.cpp"));
EXPECT(files_equal(path + "/tests/expected/Point3_StaticFunction.m" , "actual/Point3_StaticFunction.m" ));
EXPECT(files_equal(path + "/tests/expected/Point3_StaticFunction.cpp", "actual/Point3_StaticFunction.cpp"));
EXPECT(files_equal(path + "/tests/expected/@Point3/norm.m" , "actual/@Point3/norm.m" ));
EXPECT(files_equal(path + "/tests/expected/@Point3/norm.cpp" , "actual/@Point3/norm.cpp" ));

View File

@ -76,3 +76,11 @@ void emit_header_comment(ofstream& ofs, const string& delimiter) {
}
/* ************************************************************************* */
std::string maybe_shared_ptr(bool add, const std::string& type) {
string str = add? "shared_ptr<" : "";
str += type;
if (add) str += ">";
return str;
}
/* ************************************************************************* */

View File

@ -63,3 +63,6 @@ bool assert_equal(const std::string& expected, const std::string& actual);
* emit a header at the top of generated files
*/
void emit_header_comment(std::ofstream& ofs, const std::string& delimiter);
// auxiliary function to wrap an argument into a shared_ptr template
std::string maybe_shared_ptr(bool add, const std::string& type);