Merged in fix/matlab_examples_wrapper (pull request #75)

Fixing bugs in Wrap - re-creating
release/4.3a0
Zhaoyang Lv 2014-12-19 13:04:29 -05:00
commit 02e4f920d0
8 changed files with 110 additions and 59 deletions

10
gtsam.h
View File

@ -1754,6 +1754,16 @@ class Values {
template<T = {gtsam::Point2, gtsam::Point3, gtsam::Rot2, gtsam::Pose2, gtsam::Rot3, gtsam::Pose3, gtsam::Cal3_S2, gtsam::Cal3DS2, gtsam::Cal3Bundler, gtsam::EssentialMatrix, gtsam::imuBias::ConstantBias, Vector, Matrix}>
T at(size_t j);
/// Fixed size versions, for n in 1..9
void insertFixed(size_t j, Vector t, size_t n);
/// Fixed size versions, for n in 1..9
Vector atFixed(size_t j, size_t n);
/// version for double
void insertDouble(size_t j, double c);
double atDouble(size_t j) const;
};
// Actually a FastList<Key>

View File

@ -112,6 +112,24 @@ namespace gtsam {
return result;
}
/* ************************************************************************* */
Vector Values::atFixed(Key j, size_t n) {
switch (n) {
case 1: return at<Vector1>(j);
case 2: return at<Vector2>(j);
case 3: return at<Vector3>(j);
case 4: return at<Vector4>(j);
case 5: return at<Vector5>(j);
case 6: return at<Vector6>(j);
case 7: return at<Vector7>(j);
case 8: return at<Vector8>(j);
case 9: return at<Vector9>(j);
default:
throw runtime_error(
"Values::at fixed size can only handle n in 1..9");
}
}
/* ************************************************************************* */
const Value& Values::at(Key j) const {
// Find the item

View File

@ -180,6 +180,13 @@ namespace gtsam {
template<typename ValueType>
const ValueType& at(Key j) const;
/// Special version for small fixed size vectors, for matlab/python
/// throws truntime error if n<1 || n>9
Vector atFixed(Key j, size_t n);
/// version for double
double atDouble(size_t key) const { return at<double>(key);}
/** Retrieve a variable by key \c j. This version returns a reference
* to the base Value class, and needs to be casted before use.
* @param j Retrieve the value associated with this key

View File

@ -156,6 +156,7 @@ void Module::parseMarkup(const std::string& data) {
>> (*(basic.namespace_p >> str_p("::")) >> basic.className_p)[assign_a(fwDec.name)]
>> ch_p(';')
[push_back_a(forward_declarations, fwDec)]
[assign_a(cls,cls0)] // also clear class to avoid partial parse
[assign_a(fwDec, fwDec0)];
Rule module_content_p = basic.comments_p | include_p | class_p

View File

@ -363,7 +363,7 @@ void Test_arg_EigenConstRef_24(int nargout, mxArray *out[], int nargin, const mx
typedef boost::shared_ptr<Test> Shared;
checkArguments("arg_EigenConstRef",nargout,nargin-1,1);
Shared obj = unwrap_shared_ptr<Test>(in[0], "ptr_Test");
Matrix& value = *unwrap_shared_ptr< Matrix >(in[1], "ptr_Matrix");
Matrix value = unwrap< Matrix >(in[1]);
obj->arg_EigenConstRef(value);
}
@ -707,7 +707,7 @@ void MyTemplatePoint2_templatedMethod_57(int nargout, mxArray *out[], int nargin
typedef boost::shared_ptr<MyTemplatePoint2> Shared;
checkArguments("templatedMethodMatrix",nargout,nargin-1,1);
Shared obj = unwrap_shared_ptr<MyTemplatePoint2>(in[0], "ptr_MyTemplatePoint2");
Matrix& t = *unwrap_shared_ptr< Matrix >(in[1], "ptr_Matrix");
Matrix t = unwrap< Matrix >(in[1]);
out[0] = wrap< Matrix >(obj->templatedMethod<Matrix>(t));
}
@ -736,7 +736,7 @@ void MyTemplatePoint2_templatedMethod_60(int nargout, mxArray *out[], int nargin
typedef boost::shared_ptr<MyTemplatePoint2> Shared;
checkArguments("templatedMethodVector",nargout,nargin-1,1);
Shared obj = unwrap_shared_ptr<MyTemplatePoint2>(in[0], "ptr_MyTemplatePoint2");
Vector& t = *unwrap_shared_ptr< Vector >(in[1], "ptr_Vector");
Vector t = unwrap< Vector >(in[1]);
out[0] = wrap< Vector >(obj->templatedMethod<Vector>(t));
}
@ -795,7 +795,7 @@ void MyTemplateMatrix_accept_T_65(int nargout, mxArray *out[], int nargin, const
typedef boost::shared_ptr<MyTemplateMatrix> Shared;
checkArguments("accept_T",nargout,nargin-1,1);
Shared obj = unwrap_shared_ptr<MyTemplateMatrix>(in[0], "ptr_MyTemplateMatrix");
Matrix& value = *unwrap_shared_ptr< Matrix >(in[1], "ptr_Matrix");
Matrix value = unwrap< Matrix >(in[1]);
obj->accept_T(value);
}
@ -804,7 +804,7 @@ void MyTemplateMatrix_accept_Tptr_66(int nargout, mxArray *out[], int nargin, co
typedef boost::shared_ptr<MyTemplateMatrix> Shared;
checkArguments("accept_Tptr",nargout,nargin-1,1);
Shared obj = unwrap_shared_ptr<MyTemplateMatrix>(in[0], "ptr_MyTemplateMatrix");
boost::shared_ptr<Matrix> value = unwrap_shared_ptr< Matrix >(in[1], "ptr_Matrix");
Matrix value = unwrap< Matrix >(in[1]);
obj->accept_Tptr(value);
}
@ -842,7 +842,7 @@ void MyTemplateMatrix_return_T_69(int nargout, mxArray *out[], int nargin, const
typedef boost::shared_ptr<MyTemplateMatrix> Shared;
checkArguments("return_T",nargout,nargin-1,1);
Shared obj = unwrap_shared_ptr<MyTemplateMatrix>(in[0], "ptr_MyTemplateMatrix");
boost::shared_ptr<Matrix> value = unwrap_shared_ptr< Matrix >(in[1], "ptr_Matrix");
Matrix value = unwrap< Matrix >(in[1]);
out[0] = wrap< Matrix >(obj->return_T(value));
}
@ -851,7 +851,7 @@ void MyTemplateMatrix_return_Tptr_70(int nargout, mxArray *out[], int nargin, co
typedef boost::shared_ptr<MyTemplateMatrix> Shared;
checkArguments("return_Tptr",nargout,nargin-1,1);
Shared obj = unwrap_shared_ptr<MyTemplateMatrix>(in[0], "ptr_MyTemplateMatrix");
boost::shared_ptr<Matrix> value = unwrap_shared_ptr< Matrix >(in[1], "ptr_Matrix");
Matrix value = unwrap< Matrix >(in[1]);
{
SharedMatrix* ret = new SharedMatrix(obj->return_Tptr(value));
out[0] = wrap_shared_ptr(ret,"Matrix");
@ -863,8 +863,8 @@ void MyTemplateMatrix_return_ptrs_71(int nargout, mxArray *out[], int nargin, co
typedef boost::shared_ptr<MyTemplateMatrix> Shared;
checkArguments("return_ptrs",nargout,nargin-1,2);
Shared obj = unwrap_shared_ptr<MyTemplateMatrix>(in[0], "ptr_MyTemplateMatrix");
boost::shared_ptr<Matrix> p1 = unwrap_shared_ptr< Matrix >(in[1], "ptr_Matrix");
boost::shared_ptr<Matrix> p2 = unwrap_shared_ptr< Matrix >(in[2], "ptr_Matrix");
Matrix p1 = unwrap< Matrix >(in[1]);
Matrix p2 = unwrap< Matrix >(in[2]);
pair< SharedMatrix, SharedMatrix > pairResult = obj->return_ptrs(p1,p2);
{
SharedMatrix* ret = new SharedMatrix(pairResult.first);
@ -881,7 +881,7 @@ void MyTemplateMatrix_templatedMethod_72(int nargout, mxArray *out[], int nargin
typedef boost::shared_ptr<MyTemplateMatrix> Shared;
checkArguments("templatedMethodMatrix",nargout,nargin-1,1);
Shared obj = unwrap_shared_ptr<MyTemplateMatrix>(in[0], "ptr_MyTemplateMatrix");
Matrix& t = *unwrap_shared_ptr< Matrix >(in[1], "ptr_Matrix");
Matrix t = unwrap< Matrix >(in[1]);
out[0] = wrap< Matrix >(obj->templatedMethod<Matrix>(t));
}
@ -910,7 +910,7 @@ void MyTemplateMatrix_templatedMethod_75(int nargout, mxArray *out[], int nargin
typedef boost::shared_ptr<MyTemplateMatrix> Shared;
checkArguments("templatedMethodVector",nargout,nargin-1,1);
Shared obj = unwrap_shared_ptr<MyTemplateMatrix>(in[0], "ptr_MyTemplateMatrix");
Vector& t = *unwrap_shared_ptr< Vector >(in[1], "ptr_Vector");
Vector t = unwrap< Vector >(in[1]);
out[0] = wrap< Vector >(obj->templatedMethod<Vector>(t));
}

View File

@ -335,7 +335,7 @@ void Test_arg_EigenConstRef_22(int nargout, mxArray *out[], int nargin, const mx
typedef boost::shared_ptr<Test> Shared;
checkArguments("arg_EigenConstRef",nargout,nargin-1,1);
Shared obj = unwrap_shared_ptr<Test>(in[0], "ptr_Test");
Matrix& value = *unwrap_shared_ptr< Matrix >(in[1], "ptr_Matrix");
Matrix value = unwrap< Matrix >(in[1]);
obj->arg_EigenConstRef(value);
}
@ -679,7 +679,7 @@ void MyTemplatePoint2_templatedMethod_55(int nargout, mxArray *out[], int nargin
typedef boost::shared_ptr<MyTemplatePoint2> Shared;
checkArguments("templatedMethodMatrix",nargout,nargin-1,1);
Shared obj = unwrap_shared_ptr<MyTemplatePoint2>(in[0], "ptr_MyTemplatePoint2");
Matrix& t = unwrap< Matrix >(in[1]);
Matrix t = unwrap< Matrix >(in[1]);
out[0] = wrap< Matrix >(obj->templatedMethod<Matrix>(t));
}
@ -708,7 +708,7 @@ void MyTemplatePoint2_templatedMethod_58(int nargout, mxArray *out[], int nargin
typedef boost::shared_ptr<MyTemplatePoint2> Shared;
checkArguments("templatedMethodVector",nargout,nargin-1,1);
Shared obj = unwrap_shared_ptr<MyTemplatePoint2>(in[0], "ptr_MyTemplatePoint2");
Vector& t = *unwrap_shared_ptr< Vector >(in[1], "ptr_Vector");
Vector t = unwrap< Vector >(in[1]);
out[0] = wrap< Vector >(obj->templatedMethod<Vector>(t));
}
@ -767,7 +767,7 @@ void MyTemplateMatrix_accept_T_63(int nargout, mxArray *out[], int nargin, const
typedef boost::shared_ptr<MyTemplateMatrix> Shared;
checkArguments("accept_T",nargout,nargin-1,1);
Shared obj = unwrap_shared_ptr<MyTemplateMatrix>(in[0], "ptr_MyTemplateMatrix");
Matrix& value = *unwrap_shared_ptr< Matrix >(in[1], "ptr_Matrix");
Matrix value = unwrap< Matrix >(in[1]);
obj->accept_T(value);
}
@ -776,7 +776,7 @@ void MyTemplateMatrix_accept_Tptr_64(int nargout, mxArray *out[], int nargin, co
typedef boost::shared_ptr<MyTemplateMatrix> Shared;
checkArguments("accept_Tptr",nargout,nargin-1,1);
Shared obj = unwrap_shared_ptr<MyTemplateMatrix>(in[0], "ptr_MyTemplateMatrix");
boost::shared_ptr<Matrix> value = unwrap_shared_ptr< Matrix >(in[1], "ptr_Matrix");
Matrix value = unwrap< Matrix >(in[1]);
obj->accept_Tptr(value);
}
@ -814,7 +814,7 @@ void MyTemplateMatrix_return_T_67(int nargout, mxArray *out[], int nargin, const
typedef boost::shared_ptr<MyTemplateMatrix> Shared;
checkArguments("return_T",nargout,nargin-1,1);
Shared obj = unwrap_shared_ptr<MyTemplateMatrix>(in[0], "ptr_MyTemplateMatrix");
boost::shared_ptr<Matrix> value = unwrap_shared_ptr< Matrix >(in[1], "ptr_Matrix");
Matrix value = unwrap< Matrix >(in[1]);
out[0] = wrap< Matrix >(obj->return_T(value));
}
@ -823,7 +823,7 @@ void MyTemplateMatrix_return_Tptr_68(int nargout, mxArray *out[], int nargin, co
typedef boost::shared_ptr<MyTemplateMatrix> Shared;
checkArguments("return_Tptr",nargout,nargin-1,1);
Shared obj = unwrap_shared_ptr<MyTemplateMatrix>(in[0], "ptr_MyTemplateMatrix");
boost::shared_ptr<Matrix> value = unwrap_shared_ptr< Matrix >(in[1], "ptr_Matrix");
Matrix value = unwrap< Matrix >(in[1]);
{
SharedMatrix* ret = new SharedMatrix(obj->return_Tptr(value));
out[0] = wrap_shared_ptr(ret,"Matrix");
@ -835,8 +835,8 @@ void MyTemplateMatrix_return_ptrs_69(int nargout, mxArray *out[], int nargin, co
typedef boost::shared_ptr<MyTemplateMatrix> Shared;
checkArguments("return_ptrs",nargout,nargin-1,2);
Shared obj = unwrap_shared_ptr<MyTemplateMatrix>(in[0], "ptr_MyTemplateMatrix");
boost::shared_ptr<Matrix> p1 = unwrap_shared_ptr< Matrix >(in[1], "ptr_Matrix");
boost::shared_ptr<Matrix> p2 = unwrap_shared_ptr< Matrix >(in[2], "ptr_Matrix");
Matrix p1 = unwrap< Matrix >(in[1]);
Matrix p2 = unwrap< Matrix >(in[2]);
pair< SharedMatrix, SharedMatrix > pairResult = obj->return_ptrs(p1,p2);
{
SharedMatrix* ret = new SharedMatrix(pairResult.first);
@ -853,7 +853,7 @@ void MyTemplateMatrix_templatedMethod_70(int nargout, mxArray *out[], int nargin
typedef boost::shared_ptr<MyTemplateMatrix> Shared;
checkArguments("templatedMethodMatrix",nargout,nargin-1,1);
Shared obj = unwrap_shared_ptr<MyTemplateMatrix>(in[0], "ptr_MyTemplateMatrix");
Matrix& t = *unwrap_shared_ptr< Matrix >(in[1], "ptr_Matrix");
Matrix t = unwrap< Matrix >(in[1]);
out[0] = wrap< Matrix >(obj->templatedMethod<Matrix>(t));
}
@ -882,7 +882,7 @@ void MyTemplateMatrix_templatedMethod_73(int nargout, mxArray *out[], int nargin
typedef boost::shared_ptr<MyTemplateMatrix> Shared;
checkArguments("templatedMethodVector",nargout,nargin-1,1);
Shared obj = unwrap_shared_ptr<MyTemplateMatrix>(in[0], "ptr_MyTemplateMatrix");
Vector& t = *unwrap_shared_ptr< Vector >(in[1], "ptr_Vector");
Vector t = unwrap< Vector >(in[1]);
out[0] = wrap< Vector >(obj->templatedMethod<Vector>(t));
}

View File

@ -1,7 +1,7 @@
// comments!
class VectorNotEigen;
class ns::OtherClass;
virtual class ns::OtherClass;
namespace gtsam {

View File

@ -160,7 +160,6 @@ TEST( Class, Grammar ) {
EXPECT_LONGS_EQUAL(ReturnType::EIGEN, rv4.type1.category);
}
//******************************************************************************
TEST( Class, TemplateSubstition ) {
@ -171,10 +170,10 @@ TEST( Class, TemplateSubstition ) {
Template t;
ClassGrammar g(cls, t);
string markup(
string("template<T = {void, double, Matrix, Point3}> class Point2 { \n")
+ string(" T myMethod(const T& t) const; \n")
+ string("};"));
string markup(string("template<T = {void, double, Matrix, Point3}>"
"class Point2 {"
" T myMethod(const T& t) const;"
"};"));
EXPECT(parse(markup.c_str(), g, space_p).full);
@ -190,58 +189,74 @@ TEST( Class, TemplateSubstition ) {
EXPECT(assert_equal("T", rv2.type1.name()));
EXPECT_LONGS_EQUAL(ReturnType::CLASS, rv2.type1.category);
// Generate some expected values for qualified types
Qualified q_void("void", Qualified::VOID);
Qualified q_double("double", Qualified::BASIS);
Qualified q_Matrix("Matrix", Qualified::EIGEN);
Qualified q_Point3("Point3", Qualified::CLASS);
EXPECT_LONGS_EQUAL(4, t.nrValues());
EXPECT(t.argName()=="T");
EXPECT(t[0]==Qualified("void",Qualified::VOID));
EXPECT(t[1]==Qualified("double",Qualified::BASIS));
EXPECT(t[2]==Qualified("Matrix",Qualified::EIGEN));
EXPECT(t[3]==Qualified("Point3",Qualified::CLASS));
EXPECT(t[0]==q_void);
EXPECT(t[1]==q_double);
EXPECT(t[2]==q_Matrix);
EXPECT(t[3]==q_Point3);
vector<Class> classes = cls.expandTemplate(t.argName(),
t.argValues());
vector<Class> classes = cls.expandTemplate(t.argName(), t.argValues());
// check the number of new classes is four
EXPECT_LONGS_EQUAL(4, classes.size());
// check return types
EXPECT(classes[0].method("myMethod").returnValue(0).type1 == Qualified("void",Qualified::VOID));
EXPECT(classes[1].method("myMethod").returnValue(0).type1 == Qualified("double",Qualified::BASIS));
EXPECT(classes[2].method("myMethod").returnValue(0).type1 == Qualified("Matrix",Qualified::EIGEN));
EXPECT(classes[3].method("myMethod").returnValue(0).type1 == Qualified("Point3",Qualified::CLASS));
EXPECT( classes[0].method("myMethod").returnValue(0).type1 == q_void);
EXPECT( classes[1].method("myMethod").returnValue(0).type1 == q_double);
EXPECT( classes[2].method("myMethod").returnValue(0).type1 == q_Matrix);
EXPECT( classes[3].method("myMethod").returnValue(0).type1 == q_Point3);
// check the argument types
EXPECT(classes[0].method("myMethod").argumentList(0)[0].type == Qualified("void",Qualified::VOID));
EXPECT(classes[1].method("myMethod").argumentList(0)[0].type == Qualified("double",Qualified::BASIS));
EXPECT(classes[2].method("myMethod").argumentList(0)[0].type == Qualified("Matrix",Qualified::EIGEN));
EXPECT(classes[3].method("myMethod").argumentList(0)[0].type == Qualified("Point3",Qualified::CLASS));
EXPECT( classes[0].method("myMethod").argumentList(0)[0].type == q_void);
EXPECT( classes[1].method("myMethod").argumentList(0)[0].type == q_double);
EXPECT( classes[2].method("myMethod").argumentList(0)[0].type == q_Matrix);
EXPECT( classes[3].method("myMethod").argumentList(0)[0].type == q_Point3);
}
//******************************************************************************
TEST(Class, Template) {
using classic::space_p;
using classic::space_p;
// Create type grammar that will place result in cls
Class cls;
Template t;
ClassGrammar g(cls, t);
// Create type grammar that will place result in cls
Class cls;
Template t;
ClassGrammar g(cls, t);
string markup(
string(
"template<T = {Vector, Matrix}>"
" virtual class PriorFactor : gtsam::NoiseModelFactor {"
" PriorFactor(size_t key, const T& prior, const gtsam::noiseModel::Base* noiseModel); "
" T prior() const; "
" void serialize() const; "
"};"));
string markup(
string("template<T = {Vector, Matrix}>"
" virtual class PriorFactor : gtsam::NoiseModelFactor {"
" PriorFactor(size_t key, const T& prior, const gtsam::noiseModel::Base* noiseModel); "
" T prior() const; "
" void serialize() const; "
"};" ));
EXPECT(parse(markup.c_str(), g, space_p).full);
EXPECT(parse(markup.c_str(), g, space_p).full);
}
/* ************************************************************************* */
//******************************************************************************
TEST( Class, Virtualness ) {
using classic::space_p;
Class cls;
Template t;
ClassGrammar g(cls, t);
string markup("virtual class Point3 {};");
EXPECT(parse(markup.c_str(), g, space_p).full);
EXPECT(cls.isVirtual);
}
//******************************************************************************
int main() {
TestResult tr;
return TestRegistry::runAllTests(tr);
}
/* ************************************************************************* */
//******************************************************************************