From bcfcf8be8e3ad96282c9a7b645609af535629e27 Mon Sep 17 00:00:00 2001 From: lvzhaoyang Date: Fri, 12 Dec 2014 11:34:34 -0500 Subject: [PATCH] fix gtsam wrapper for priorFactorVector --- gtsam.h | 2 +- wrap/Argument.cpp | 6 +++--- wrap/tests/expected2/geometry_wrapper.cpp | 2 +- wrap/tests/testClass.cpp | 22 ++++++++++++++++++++++ 4 files changed, 27 insertions(+), 5 deletions(-) diff --git a/gtsam.h b/gtsam.h index caac58750..25c34ebd1 100644 --- a/gtsam.h +++ b/gtsam.h @@ -2154,7 +2154,7 @@ class NonlinearISAM { #include #include -template +template virtual class PriorFactor : gtsam::NoiseModelFactor { PriorFactor(size_t key, const T& prior, const gtsam::noiseModel::Base* noiseModel); T prior() const; diff --git a/wrap/Argument.cpp b/wrap/Argument.cpp index 1f57917d8..848998eb0 100644 --- a/wrap/Argument.cpp +++ b/wrap/Argument.cpp @@ -78,11 +78,11 @@ void Argument::matlab_unwrap(FileWriter& file, const string& matlabName) const { string cppType = type.qualifiedName("::"); string matlabUniqueType = type.qualifiedName(); - if (is_ptr) + if (is_ptr && type.category != Qualified::EIGEN) // A pointer: emit an "unwrap_shared_ptr" call which returns a pointer file.oss << "boost::shared_ptr<" << cppType << "> " << name << " = unwrap_shared_ptr< "; - else if (is_ref) + else if (is_ref && type.category != Qualified::EIGEN) // A reference: emit an "unwrap_shared_ptr" call and de-reference the pointer file.oss << cppType << "& " << name << " = *unwrap_shared_ptr< "; else @@ -94,7 +94,7 @@ void Argument::matlab_unwrap(FileWriter& file, const string& matlabName) const { file.oss << cppType << " " << name << " = unwrap< "; file.oss << cppType << " >(" << matlabName; - if (is_ptr || is_ref) + if( (is_ptr || is_ref) && type.category != Qualified::EIGEN) file.oss << ", \"ptr_" << matlabUniqueType << "\""; file.oss << ");" << endl; } diff --git a/wrap/tests/expected2/geometry_wrapper.cpp b/wrap/tests/expected2/geometry_wrapper.cpp index 82926e2ce..1c8403ac9 100644 --- a/wrap/tests/expected2/geometry_wrapper.cpp +++ b/wrap/tests/expected2/geometry_wrapper.cpp @@ -679,7 +679,7 @@ void MyTemplatePoint2_templatedMethod_55(int nargout, mxArray *out[], int nargin typedef boost::shared_ptr Shared; checkArguments("templatedMethodMatrix",nargout,nargin-1,1); Shared obj = unwrap_shared_ptr(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(t)); } diff --git a/wrap/tests/testClass.cpp b/wrap/tests/testClass.cpp index f7d9a3ade..ea86a174c 100644 --- a/wrap/tests/testClass.cpp +++ b/wrap/tests/testClass.cpp @@ -217,6 +217,28 @@ TEST( Class, TemplateSubstition ) { } +TEST(Class, Template) { + + + using classic::space_p; + + // Create type grammar that will place result in cls + Class cls; + Template t; + ClassGrammar g(cls, t); + + string markup( + string("template" + " 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); + +} + /* ************************************************************************* */ int main() { TestResult tr;