fix gtsam wrapper for priorFactorVector

release/4.3a0
lvzhaoyang 2014-12-12 11:34:34 -05:00
parent 6d97b8d3db
commit bcfcf8be8e
4 changed files with 27 additions and 5 deletions

View File

@ -2154,7 +2154,7 @@ class NonlinearISAM {
#include <gtsam/geometry/StereoPoint2.h>
#include <gtsam/slam/PriorFactor.h>
template<T = { Vector, Matrix, gtsam::Point2, gtsam::StereoPoint2, gtsam::Point3, gtsam::Rot2, gtsam::Rot3, gtsam::Pose2, gtsam::Pose3, gtsam::Cal3_S2,gtsam::CalibratedCamera, gtsam::SimpleCamera, gtsam::imuBias::ConstantBias}>
template<T = {Vector, gtsam::Point2, gtsam::StereoPoint2, gtsam::Point3, gtsam::Rot2, gtsam::Rot3, gtsam::Pose2, gtsam::Pose3, gtsam::Cal3_S2,gtsam::CalibratedCamera, gtsam::SimpleCamera, gtsam::imuBias::ConstantBias}>
virtual class PriorFactor : gtsam::NoiseModelFactor {
PriorFactor(size_t key, const T& prior, const gtsam::noiseModel::Base* noiseModel);
T prior() const;

View File

@ -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;
}

View File

@ -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_shared_ptr< Matrix >(in[1], "ptr_Matrix");
Matrix& t = unwrap< Matrix >(in[1]);
out[0] = wrap< Matrix >(obj->templatedMethod<Matrix>(t));
}

View File

@ -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<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);
}
/* ************************************************************************* */
int main() {
TestResult tr;