From 726bed11b83c9cde04235ca5e8416d869c1b181d Mon Sep 17 00:00:00 2001 From: Alex Cunningham Date: Tue, 8 Mar 2011 19:19:21 +0000 Subject: [PATCH] Removed exports for SharedGaussian and SharedDiagonal and moved them to testSerialization --- gtsam/linear/SharedDiagonal.h | 3 --- gtsam/linear/SharedGaussian.h | 4 ---- tests/testSerialization.cpp | 3 +++ 3 files changed, 3 insertions(+), 7 deletions(-) diff --git a/gtsam/linear/SharedDiagonal.h b/gtsam/linear/SharedDiagonal.h index 6564a3c7e..da62cb667 100644 --- a/gtsam/linear/SharedDiagonal.h +++ b/gtsam/linear/SharedDiagonal.h @@ -18,8 +18,6 @@ #pragma once -#include -#include #include namespace gtsam { // note, deliberately not in noiseModel namespace @@ -71,4 +69,3 @@ namespace gtsam { // note, deliberately not in noiseModel namespace } -BOOST_CLASS_EXPORT_GUID(gtsam::SharedDiagonal, "gtsam_SharedDiagonal") diff --git a/gtsam/linear/SharedGaussian.h b/gtsam/linear/SharedGaussian.h index 7239556f7..7a23e3c51 100644 --- a/gtsam/linear/SharedGaussian.h +++ b/gtsam/linear/SharedGaussian.h @@ -18,8 +18,6 @@ #pragma once -#include -#include #include namespace gtsam { // note, deliberately not in noiseModel namespace @@ -77,5 +75,3 @@ namespace gtsam { // note, deliberately not in noiseModel namespace } }; } - -BOOST_CLASS_EXPORT_GUID(gtsam::SharedGaussian, "gtsam_SharedGaussian") diff --git a/tests/testSerialization.cpp b/tests/testSerialization.cpp index c98000564..696952bff 100644 --- a/tests/testSerialization.cpp +++ b/tests/testSerialization.cpp @@ -203,6 +203,9 @@ 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::SharedGaussian, "gtsam_SharedGaussian"); +BOOST_CLASS_EXPORT_GUID(gtsam::SharedDiagonal, "gtsam_SharedDiagonal"); + /* ************************************************************************* */ // example noise models noiseModel::Diagonal::shared_ptr diag3 = noiseModel::Diagonal::Sigmas(Vector_(3, 0.1, 0.2, 0.3));