gtsam serialize matlab and cpp not working.
Hi, I am trying to serialize object in cpp, and receive it on matlab. I am using gtsam 4 for testing. also happen in 3.2.1 It doesn't work, so i create "identical" program will generate the same factor graph, and hopefully the same serialize string. My program in cpp: (I didn't write all the export_boost_before. it long text. but i can write if you need it.).
gtsam::Key i1 = gtsam::symbol('x',1);
gtsam::Key i2 = gtsam::symbol('x',2);
gtsam::Key i3 = gtsam::symbol('x',3);
gtsam::Key j1 = gtsam::symbol('l',1);
gtsam::Key j2 = gtsam::symbol('l',2);
gtsam::NonlinearFactorGraph graph;
gtsam::Pose2 priorMean = gtsam::Pose2(0.0, 0.0, 0.0);
gtsam::Vector sigma_p(3);
sigma_p << 0.3, 0.3, 0.1;
gtsam::SharedNoiseModel priorNoise = gtsam::noiseModel::Diagonal::Sigmas(sigma_p);
PriorFactorPose2 prior = PriorFactorPose2(i1, priorMean, priorNoise);
graph.add(prior);
std::string serialized2 = gtsam::serialize(graph);
std::cout << "\"" << serialized2 << "\"\n\n\n";
program in matlab:
i1 = gtsam.symbol('x',1);
i2 = gtsam.symbol('x',2);
i3 = gtsam.symbol('x',3);
j1 = gtsam.symbol('l',1);
j2 = gtsam.symbol('l',2);
graph = gtsam.NonlinearFactorGraph;
priorMean = gtsam.Pose2(0.0, 0.0, 0.0); % prior at origin
priorNoise = gtsam.noiseModel.Diagonal.Sigmas([0.3; 0.3; 0.1]);
graph.add(gtsam.PriorFactorPose2(i1, priorMean, priorNoise)); % add directly to graph
graph.string_serialize
output of cpp:
22 serialization::archive 12 0 0 0 0 0 0 0 0 1 1 0 1 5 21 gtsamPriorFactorPose2 1 0
0 0 0 0 0 0 0 0 0 0 0 1 0 8646911284551352321 0 1 12 23 gtsamnoiseModelDiagonal 1 0
1 1 0
2 0 0 3 0 0 0 0 0 3 2.99999999999999989e-01 2.99999999999999989e-01 1.00000000000000006e-01 3 3.33333333333333348e+00 3.33333333333333348e+00 1.00000000000000000e+01 0 0 0 0 0 0 0.00000000000000000e+00 0.00000000000000000e+00 0 0 1.00000000000000000e+00 0.00000000000000000e+00
output of matlab:
22 serialization::archive 11 1 0
0 0 0 0 0 0 0 1 1 0 1 5 21 gtsamPriorFactorPose2 1 0
1 0 0 0 0 0 0 1 0
2 0 0 1 0 8646911284551352321 0 1 12 23 gtsamnoiseModelDiagonal 1 0
3 1 0
4 0 0 3 0 0 0 0 0 3 2.99999999999999989e-01 2.99999999999999989e-01 1.00000000000000006e-01 3 3.33333333333333348e+00 3.33333333333333348e+00 1.00000000000000000e+01 1 0
5 1 0
6 0 0 0.00000000000000000e+00 0.00000000000000000e+00 1 0
7 1.00000000000000000e+00 0.00000000000000000e+00
I notice the serialization::archive is different version (11 1 against 12).
Can you help me solve that issue?
@dellaert @jdong37 @cbeall3
Comments (27)
-
-
- marked as minor
-
-
assigned issue to
-
assigned issue to
-
- changed status to closed
Marking as closed.
-
reporter You close it without fix it?
-
The ticket was closed given no response. Has the issue been isolated?
-
reporter What response are you looking for? I gave an example to reproduce the problem. Are you try it?
-
- changed status to open
-
Tal, are you sure the MATLAB wrapper and C++ libraries were compiled at the same time and with same version of Boost?
-
@sasza85 can you try to repro?
-
I can try to reproduce. I'm having some trouble with serialization in MATLAB, so I'd like to take a look here first and then ask my question if I can't figure it out from looking at this.
@talregev You said
(I didn't write all the export_boost_before. it long text. but i can write if you need it.).
Could you please add your complete .cpp?
I'm currently rebuilding GTSAM and the MATLAB toolbox from scratch to try to make sure I don't have any version shenanigans.
-
Partial reproduction. I don't have have an archive version mismatch, but the C++ and MATLAB outputs are different. Here's the .cpp
#include <gtsam/base/serialization.h> #include <gtsam/base/serializationTestHelpers.h> #include <gtsam/geometry/Pose2.h> #include <gtsam/slam/BetweenFactor.h> #include <gtsam/slam/PriorFactor.h> #include <gtsam/inference/Symbol.h> #include <gtsam/nonlinear/NonlinearFactorGraph.h> using namespace std; using namespace gtsam; using namespace gtsam::serializationTestHelpers; // Creating as many permutations of factors as possible typedef PriorFactor<Pose2> PriorFactorPose2; typedef BetweenFactor<Pose2> BetweenFactorPose2; /* Create GUIDs for Noisemodels */ /* ************************************************************************* */ BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::Constrained, "gtsam_noiseModel_Constrained"); BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::Diagonal, "gtsam_noiseModel_Diagonal"); BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::Gaussian, "gtsam_noiseModel_Gaussian"); BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::Unit, "gtsam_noiseModel_Unit"); BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::Isotropic, "gtsam_noiseModel_Isotropic"); BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::Robust, "gtsam_noiseModel_Robust"); BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::mEstimator::Base , "gtsam_noiseModel_mEstimator_Base"); BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::mEstimator::Null , "gtsam_noiseModel_mEstimator_Null"); BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::mEstimator::Fair , "gtsam_noiseModel_mEstimator_Fair"); BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::mEstimator::Huber, "gtsam_noiseModel_mEstimator_Huber"); BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::mEstimator::Tukey, "gtsam_noiseModel_mEstimator_Tukey"); BOOST_CLASS_EXPORT_GUID(gtsam::SharedNoiseModel, "gtsam_SharedNoiseModel"); BOOST_CLASS_EXPORT_GUID(gtsam::SharedDiagonal, "gtsam_SharedDiagonal"); /* Create GUIDs for geometry */ /* ************************************************************************* */ GTSAM_VALUE_EXPORT(gtsam::Pose2); /* Create GUIDs for factors */ /* ************************************************************************* */ BOOST_CLASS_EXPORT_GUID(PriorFactorPose2, "gtsam::PriorFactorPose2"); BOOST_CLASS_EXPORT_GUID(BetweenFactorPose2, "gtsam::BetweenFactorPose2"); int main(int argc, char** argv) { gtsam::Key i1 = gtsam::symbol('x',1); gtsam::Key i2 = gtsam::symbol('x',2); gtsam::Key i3 = gtsam::symbol('x',3); gtsam::Key j1 = gtsam::symbol('l',1); gtsam::Key j2 = gtsam::symbol('l',2); gtsam::NonlinearFactorGraph graph; gtsam::Pose2 priorMean = gtsam::Pose2(0.0, 0.0, 0.0); gtsam::Vector sigma_p(3); sigma_p << 0.3, 0.3, 0.1; gtsam::SharedNoiseModel priorNoise = gtsam::noiseModel::Diagonal::Sigmas(sigma_p); PriorFactorPose2 prior = PriorFactorPose2(i1, priorMean, priorNoise); graph.add(prior); gtsam::Pose2 odometry = gtsam::Pose2(2.0, 0.0, 0.0); gtsam::Vector sigma(3); sigma << 0.2, 0.2, 0.2; gtsam::SharedNoiseModel odometryNoise = gtsam::noiseModel::Diagonal::Sigmas(sigma); graph.add(BetweenFactorPose2(i1, i2, odometry, odometryNoise)); graph.add(BetweenFactorPose2(i2, i3, odometry, odometryNoise)); std::string serialized; serialized = gtsam::serialize(graph); std::cout << serialized; std::string OutputFile("TalSerializationTest.test"); std::ofstream OfsOutput(OutputFile.c_str()); boost::archive::text_oarchive OaOutput(OfsOutput); OaOutput << graph; OfsOutput.close(); return 0; }
The output is
22 serialization::archive 12 0 0 0 0 0 0 0 0 3 1 0 1 5 23 gtsam::PriorFactorPose2 1 0 0 0 0 0 0 0 0 0 0 1 0 8646911284551352321 0 1 12 25 gtsam_noiseModel_Diagonal 1 0 1 1 0 2 0 0 3 0 0 0 0 0 3 2.99999999999999989e-01 2.99999999999999989e-01 1.00000000000000006e-01 3 3.33333333333333348e+00 3.33333333333333348e+00 1.00000000000000000e+01 0 0 0 0 0 0 0.00000000000000000e+00 0.00000000000000000e+00 0 0 1.00000000000000000e+00 0.00000000000000000e+00 21 25 gtsam::BetweenFactorPose2 1 0 3 0 0 2 0 8646911284551352321 8646911284551352322 23 26 gtsam_noiseModel_Isotropic 1 0 4 5 6 3 0 3 2.00000000000000011e-01 2.00000000000000011e-01 2.00000000000000011e-01 3 5.00000000000000000e+00 5.00000000000000000e+00 5.00000000000000000e+00 2.00000000000000011e-01 5.00000000000000000e+00 2.00000000000000000e+00 0.00000000000000000e+00 1.00000000000000000e+00 0.00000000000000000e+00 21 7 2 0 8646911284551352322 8646911284551352323 23 4 2.00000000000000000e+00 0.00000000000000000e+00 1.00000000000000000e+00 0.00000000000000000e+00
Running
cat
onTalSerializationTest.test
produces the same output.In MATLAB, I run
i1 = gtsam.symbol('x',1); i2 = gtsam.symbol('x',2); i3 = gtsam.symbol('x',3); j1 = gtsam.symbol('l',1); j2 = gtsam.symbol('l',2); graph = gtsam.NonlinearFactorGraph; priorMean = gtsam.Pose2(0.0, 0.0, 0.0); % prior at origin priorNoise = gtsam.noiseModel.Diagonal.Sigmas([0.3; 0.3; 0.1]); graph.add(gtsam.PriorFactorPose2(i1, priorMean, priorNoise)); % add directly to graph graph.string_serialize
The output is
'22 serialization::archive 12 1 0 0 0 0 0 0 0 0 1 1 0 1 5 21 gtsamPriorFactorPose2 1 0 1 0 0 0 0 0 0 1 0 2 1 0 8646911284551352321 0 1 12 23 gtsamnoiseModelDiagonal 1 0 3 1 0 4 0 0 3 0 0 0 0 0 3 2.99999999999999989e-01 2.99999999999999989e-01 1.00000000000000006e-01 3 3.33333333333333348e+00 3.33333333333333348e+00 1.00000000000000000e+01 1 0 5 1 0 6 0 0 0.00000000000000000e+00 0.00000000000000000e+00 1 0 7 1.00000000000000000e+00 0.00000000000000000e+00'
If I run
TalSerializedString = fileread('TalSerializationTest.test') TalData = gtsam.NonlinearFactorGraph.string_deserialize(TalSerializedString)
I get
Error using gtsam_wrapper Exception from gtsam: unregistered class Error in gtsam.NonlinearFactorGraph.string_deserialize (line 230) varargout{1} = gtsam_wrapper(1119, varargin{:});
Is
TalData = gtsam.NonlinearFactorGraph.string_deserialize(TalSerializedString)
the command I want to be running? I have successfully used that for simple types, like an individualPose2
orVectorValues
. -
Also, if I modify the end of the MATLAB script to read
MatlabSerializedGraph = graph.string_serialize; DeserializedMatlabGraph = ... gtsam.NonlinearFactorGraph.string_deserialize(MatlabSerializedGraph);
then
>> DeserializedMatlabGraph size: 1 Factor 0: PriorFactor on x1 prior mean: (0, 0, 0) noise model: diagonal sigmas[0.3; 0.3; 0.1];
-
I think you should use the
>>
operator of a text input archive... -
Oh, sorry, that's not a stream operator -- just the
>>
indicating the 'prompt' in MATLAB. I just meant that when I printDeserializedMatlabGraph
to the console in MATLAB, the stuff below that is what is printed. -
What happens if you just use >> in C++ to read the graph back? Does that work? That is the code that is (should) be created by wrap, in the method
Class::deserialization_fragments
in wrap. -
It seems to be okay. I added
std::ifstream IfsInput(OutputFile.c_str()); boost::archive::text_iarchive IaInput(IfsInput); gtsam::NonlinearFactorGraph DeserializedGraphCpp; IaInput >> DeserializedGraphCpp; cout << "Deserialized factor graph: " << endl; DeserializedGraphCpp.print(); IfsInput.close();
and saw
Deserialized factor graph: NonlinearFactorGraph: size: 3 Factor 0: PriorFactor on x1 prior mean: (0, 0, 0) noise model: diagonal sigmas[0.3; 0.3; 0.1]; Factor 1: BetweenFactor(x1,x2) measured: (2, 0, 0) isotropic dim=3 sigma=0.2 Factor 2: BetweenFactor(x2,x3) measured: (2, 0, 0) isotropic dim=3 sigma=0.2
-
OK. can you check the generated cpp code for the wrapper? maybe that is doing something different. Note there seem to be two graphs you're building, one of size 3 in c++ one of size 1 in MATLAB? Confused as to what is going on now.
-
If I understand how this works (big if), then the code that was emitted is in the build directory in
wrap/gtsam/gtsam_wrapper.cpp
and isvoid gtsamNonlinearFactorGraph_string_deserialize_1119(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr<gtsam::NonlinearFactorGraph> Shared; checkArguments("gtsamNonlinearFactorGraph.string_deserialize",nargout,nargin,1); string serialized = unwrap< string >(in[0]); istringstream in_archive_stream(serialized); boost::archive::text_iarchive in_archive(in_archive_stream); Shared output(new gtsam::NonlinearFactorGraph()); in_archive >> *output; out[0] = wrap_shared_ptr(output,"gtsam.NonlinearFactorGraph", false); }
There are two graphs, because I was trying to cobble together what the reporter was doing (he started on
#307-- that's part of the reason why I asked him to paste his entire code, so I could run exactly what he did). I think in the MATLAB, he might have been backing off of his full example to demonstrate the problem.When I realized the two graphs were different, I tried paring down the C++ code so that it too only had the Pose2 prior factor, and it didn't seem to make a difference. Like that (just one prior), the output (in C++) is
22 serialization::archive 12 0 0 0 0 0 0 0 0 1 1 0 1 5 23 gtsam::PriorFactorPose2 1 0 0 0 0 0 0 0 0 0 0 1 0 8646911284551352321 0 1 12 25 gtsam_noiseModel_Diagonal 1 0 1 1 0 2 0 0 3 0 0 0 0 0 3 2.99999999999999989e-01 2.99999999999999989e-01 1.00000000000000006e-01 3 3.33333333333333348e+00 3.33333333333333348e+00 1.00000000000000000e+01 0 0 0 0 0 0 0.00000000000000000e+00 0.00000000000000000e+00 0 0 1.00000000000000000e+00 0.00000000000000000e+00 Deserialized factor graph: NonlinearFactorGraph: size: 1 Factor 0: PriorFactor on x1 prior mean: (0, 0, 0) noise model: diagonal sigmas[0.3; 0.3; 0.1];
and MATLAB still barfs if I try to run
gtsam.NonlinearFactorGraph.string_deserialize()
on a string containing the serialized graph, withError using gtsam_wrapper Exception from gtsam: unregistered class Error in gtsam.NonlinearFactorGraph.string_deserialize (line 230) varargout{1} = gtsam_wrapper(1119, varargin{:});
EDIT 2018-1106 1327 PST I accidentally pasted the cpp code for
GaussianFactorGraph
. It is now replaced by the code forNonlinearFactorGraph
(I noticed that the MATLAB error mentioned 1119, and I had pasted 903) -
OK, in MATLAB:
22 serialization::archive 12 1 0 0 0 0 0 0 0 0 1 1 0 1 5 21 gtsamPriorFactorPose2 1 0 1 0 0 0 0 0 0 1 0 2 1 0 8646911284551352321 0 1 12 23 gtsamnoiseModelDiagonal 1 0 3 1 0 4 0 0 3 0 0 0 0 0 3 2.99999999999999989e-01 2.99999999999999989e-01 1.00000000000000006e-01 3 3.33333333333333348e+00 3.33333333333333348e+00 1.00000000000000000e+01 1 0 5 1 0 6 0 0 0.00000000000000000e+00 0.00000000000000000e+00 1 0 7 1.00000000000000000e+00 0.00000000000000000e+00
and in c++
22 serialization::archive 12 0 0 0 0 0 0 0 0 1 1 0 1 5 23 gtsam::PriorFactorPose2 1 0 0 0 0 0 0 0 0 0 0 1 0 8646911284551352321 0 1 12 25 gtsam_noiseModel_Diagonal 1 0 1 1 0 2 0 0 3 0 0 0 0 0 3 2.99999999999999989e-01 2.99999999999999989e-01 1.00000000000000006e-01 3 3.33333333333333348e+00 3.33333333333333348e+00 1.00000000000000000e+01 0 0 0 0 0 0 0.00000000000000000e+00 0.00000000000000000e+00 0 0 1.00000000000000000e+00 0.00000000000000000e+00
Aha, a clue: the difference is in the names of the classes... So, when the wrapper is compiled the name seems different, and that is the source of the incompatibility. Now, the riddle is why they would be different :-)
-
Both (prior factor pose2 and noise model diagonal) class names seem to be different.
gtsam::noiseModel::Diagonal
seems to be more different. Is this a result of howtyepdef
is used?Just to make sure we're on the same page, this is my current complete .cpp file:
#include <gtsam/base/serialization.h> #include <gtsam/base/serializationTestHelpers.h> #include <gtsam/geometry/Pose2.h> #include <gtsam/inference/Symbol.h> #include <gtsam/nonlinear/NonlinearFactorGraph.h> #include <gtsam/slam/PriorFactor.h> using namespace std; using namespace gtsam; using namespace gtsam::serializationTestHelpers; // Creating as many permutations of factors as possible typedef PriorFactor<Pose2> PriorFactorPose2; /* Create GUIDs for Noisemodels */ /* ************************************************************************* */ BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::Constrained, "gtsam_noiseModel_Constrained"); BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::Diagonal, "gtsam_noiseModel_Diagonal"); BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::Gaussian, "gtsam_noiseModel_Gaussian"); BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::Unit, "gtsam_noiseModel_Unit"); BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::Isotropic, "gtsam_noiseModel_Isotropic"); BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::Robust, "gtsam_noiseModel_Robust"); BOOST_CLASS_EXPORT_GUID(gtsam::SharedNoiseModel, "gtsam_SharedNoiseModel"); BOOST_CLASS_EXPORT_GUID(gtsam::SharedDiagonal, "gtsam_SharedDiagonal"); /* Create GUIDs for geometry */ /* ************************************************************************* */ GTSAM_VALUE_EXPORT(gtsam::Pose2); /* Create GUIDs for factors */ /* ************************************************************************* */ BOOST_CLASS_EXPORT_GUID(PriorFactorPose2, "gtsam::PriorFactorPose2"); int main(int argc, char** argv) { gtsam::Key i1 = gtsam::symbol('x',1); gtsam::Key i2 = gtsam::symbol('x',2); gtsam::Key i3 = gtsam::symbol('x',3); gtsam::Key j1 = gtsam::symbol('l',1); gtsam::Key j2 = gtsam::symbol('l',2); gtsam::NonlinearFactorGraph graph; gtsam::Pose2 priorMean = gtsam::Pose2(0.0, 0.0, 0.0); gtsam::Vector sigma_p(3); sigma_p << 0.3, 0.3, 0.1; gtsam::SharedNoiseModel priorNoise = gtsam::noiseModel::Diagonal::Sigmas(sigma_p); PriorFactorPose2 prior = PriorFactorPose2(i1, priorMean, priorNoise); graph.add(prior); std::string serialized; serialized = gtsam::serialize(graph); std::cout << serialized << endl; std::string OutputFile("TalSerializationTest.test"); std::ofstream OfsOutput(OutputFile.c_str()); boost::archive::text_oarchive OaOutput(OfsOutput); OaOutput << graph; OfsOutput.close(); std::ifstream IfsInput(OutputFile.c_str()); boost::archive::text_iarchive IaInput(IfsInput); gtsam::NonlinearFactorGraph DeserializedGraphCpp; IaInput >> DeserializedGraphCpp; cout << "Deserialized factor graph: " << endl; DeserializedGraphCpp.print(); IfsInput.close(); return 0; }
-
Aha. What are those BOOST_CLASS_EXPORT_GUID statements? I forget. But I think there's the rub.
-
Aha. What are those BOOST_CLASS_EXPORT_GUID statements? I forget. But I think there's the rub.
I assume you're right. For what it's worth, I have no idea what I'm doing. In
#307, Jing Dong had mentioned that those statements were necessary, but I don't see them sprinkled around the code (the examples) very much.If I comment, say,
BOOST_CLASS_EXPORT_GUID(PriorFactorPose2, "gtsam::PriorFactorPose2");
, I get (at run-time)terminate called after throwing an instance of 'boost::archive::archive_exception' what(): unregistered class - derived class not registered or exported
I thought having
void serialize()
in a class definition and using the wrapper was supposed to make the magic happen for wrapped classes, but I have an extremely limited understanding of what's going on there (I'm talking about the MATLAB here, having seen the same error coming out of MATLAB).It seems like having different names is going to be a problem, and we can only have the same names by
typedef
(is that true?), so perhaps I need to understand the name (for lack of a better word) mangling.In terms of a runnable example (no runtime crash), the minimum set of funny statements is
typedef PriorFactor<Pose2> PriorFactorPose2; BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::Diagonal, "gtsam_noiseModel_Diagonal"); BOOST_CLASS_EXPORT_GUID(gtsam::SharedNoiseModel, "gtsam_SharedNoiseModel"); BOOST_CLASS_EXPORT_GUID(PriorFactorPose2, "gtsam::PriorFactorPose2");
That's eliminating all of the other macros, including
GTSAM_VALUE_EXPORT(gtsam::Pose2);
-
Okay, I got it. I think it is just the printed names as the second argument to the macros. Running
#include <gtsam/base/serialization.h> #include <gtsam/base/serializationTestHelpers.h> #include <gtsam/geometry/Pose2.h> #include <gtsam/inference/Symbol.h> #include <gtsam/nonlinear/NonlinearFactorGraph.h> #include <gtsam/slam/PriorFactor.h> using namespace std; using namespace gtsam; using namespace gtsam::serializationTestHelpers; // Creating as many permutations of factors as possible typedef PriorFactor<Pose2> PriorFactorPose2; /* Create GUIDs for Noisemodels */ /* ************************************************************************* */ BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::Diagonal, "gtsamnoiseModelDiagonal"); BOOST_CLASS_EXPORT_GUID(gtsam::SharedNoiseModel, "gtsamSharednoiseMode"); /* Create GUIDs for factors */ /* ************************************************************************* */ BOOST_CLASS_EXPORT_GUID(PriorFactorPose2, "gtsamPriorFactorPose2"); int main(int argc, char** argv) { gtsam::Key i1 = gtsam::symbol('x',1); gtsam::Key i2 = gtsam::symbol('x',2); gtsam::Key i3 = gtsam::symbol('x',3); gtsam::Key j1 = gtsam::symbol('l',1); gtsam::Key j2 = gtsam::symbol('l',2); gtsam::NonlinearFactorGraph graph; gtsam::Pose2 priorMean = gtsam::Pose2(0.0, 0.0, 0.0); gtsam::Vector sigma_p(3); sigma_p << 0.3, 0.3, 0.1; gtsam::SharedNoiseModel priorNoise = gtsam::noiseModel::Diagonal::Sigmas(sigma_p); PriorFactorPose2 prior = PriorFactorPose2(i1, priorMean, priorNoise); graph.add(prior); std::string serialized; serialized = gtsam::serialize(graph); std::cout << serialized << endl; std::string OutputFile("TalSerializationTest.test"); std::ofstream OfsOutput(OutputFile.c_str()); boost::archive::text_oarchive OaOutput(OfsOutput); OaOutput << graph; OfsOutput.close(); std::ifstream IfsInput(OutputFile.c_str()); boost::archive::text_iarchive IaInput(IfsInput); gtsam::NonlinearFactorGraph DeserializedGraphCpp; IaInput >> DeserializedGraphCpp; cout << "Deserialized factor graph: " << endl; DeserializedGraphCpp.print(); IfsInput.close(); return 0; }
gives
22 serialization::archive 12 0 0 0 0 0 0 0 0 1 1 0 1 5 21 gtsamPriorFactorPose2 1 0 0 0 0 0 0 0 0 0 0 1 0 8646911284551352321 0 1 12 23 gtsamnoiseModelDiagonal 1 0 1 0 0 0 0 3 0 0 0 0 0 3 2.99999999999999989e-01 2.99999999999999989e-01 1.00000000000000006e-01 3 3.33333333333333348e+00 3.33333333333333348e+00 1.00000000000000000e+01 0 0 0 0 0 0 0.00000000000000000e+00 0.00000000000000000e+00 0 0 1.00000000000000000e+00 0.00000000000000000e+00 Deserialized factor graph: NonlinearFactorGraph: size: 1 Factor 0: PriorFactor on x1 prior mean: (0, 0, 0) noise model: diagonal sigmas[0.3; 0.3; 0.1];
and then, in MATLAB,
TalSerializedString = fileread('TalSerializationTest.test'); TalData = gtsam.NonlinearFactorGraph.string_deserialize(TalSerializedString)
gives back
size: 1 Factor 0: PriorFactor on x1 prior mean: (0, 0, 0) noise model: diagonal sigmas[0.3; 0.3; 0.1];
Now, the reason I got interested in this issue is that I was trying to serialize
gtsam::Values
and having MATLAB barf when I tried to deserialize it. If there's a name mismatch there, the fix might be more ... interesting as I don't supply the inputs to the macro for that serialization (I don't think). I'll investigate later. Maybe tonight.@talregev Can you look at how I modified your code (mostly matching up the second argument to
BOOST_CLASS_EXPORT_GUID
to match the value that is used by MATLAB, which I think is automatically generated byClass.cpp
inwrap
, but can be teased out by examining the serialized strings from C++ and MATLAB) to see if your issue is resolved? If you have archive number mismatches, I think there's a good chance that something is out of date, and I don't think this part will help, but I couldn't run your example without archive number mismatches, so this might help. -
Awesome! I think the wrapper must have them somewhere. Just do a global search in the repo and you’ll figure it out I think.
-
@talregev ping :)
I produced code that should solve his problem, and the issue that I was thinking about regarding serialization of
Values
should have been fixed by#361. If I still have a question, I can open a new issue.If Tal doesn't come back with questions, I recommend closing the issue.
-
- changed status to resolved
Mike gave a working example. Ideally there would be a unit test for this but we don't currently run MATLAB unit tests in CI, and even if we did this is a mixed language unit test. Hard to do.
- Log in to comment
Hmmm. This might take some investigation on your part. If I was doing this, I'd create a failing unit test that isolates the issue, then look for a fix.