Changed -inl.h use with Values and TupleValues, removed instantiation macros for Values and TupleValues

release/4.3a0
Alex Cunningham 2011-11-17 22:44:46 +00:00
parent 96f77466c6
commit 8bc83d4219
25 changed files with 16 additions and 72 deletions

View File

@ -34,7 +34,7 @@
#include <gtsam/slam/BearingRangeFactor.h> #include <gtsam/slam/BearingRangeFactor.h>
// implementations for structures - needed if self-contained, and these should be included last // implementations for structures - needed if self-contained, and these should be included last
#include <gtsam/nonlinear/TupleValues-inl.h> #include <gtsam/nonlinear/TupleValues.h>
#include <gtsam/nonlinear/NonlinearFactorGraph-inl.h> #include <gtsam/nonlinear/NonlinearFactorGraph-inl.h>
#include <gtsam/nonlinear/NonlinearOptimizer-inl.h> #include <gtsam/nonlinear/NonlinearOptimizer-inl.h>
#include <gtsam/linear/GaussianSequentialSolver.h> #include <gtsam/linear/GaussianSequentialSolver.h>

View File

@ -23,7 +23,7 @@
#include <gtsam/geometry/Rot2.h> #include <gtsam/geometry/Rot2.h>
#include <gtsam/linear/NoiseModel.h> #include <gtsam/linear/NoiseModel.h>
#include <gtsam/nonlinear/Key.h> #include <gtsam/nonlinear/Key.h>
#include <gtsam/nonlinear/Values-inl.h> #include <gtsam/nonlinear/Values.h>
#include <gtsam/nonlinear/NonlinearFactorGraph-inl.h> #include <gtsam/nonlinear/NonlinearFactorGraph-inl.h>
#include <gtsam/nonlinear/NonlinearOptimization-inl.h> #include <gtsam/nonlinear/NonlinearOptimization-inl.h>

View File

@ -24,7 +24,7 @@
#include <gtsam/nonlinear/ExtendedKalmanFilter-inl.h> #include <gtsam/nonlinear/ExtendedKalmanFilter-inl.h>
#include <gtsam/slam/PriorFactor.h> #include <gtsam/slam/PriorFactor.h>
#include <gtsam/slam/BetweenFactor.h> #include <gtsam/slam/BetweenFactor.h>
#include <gtsam/nonlinear/Values-inl.h> #include <gtsam/nonlinear/Values.h>
#include <gtsam/geometry/Point2.h> #include <gtsam/geometry/Point2.h>
using namespace std; using namespace std;

View File

@ -22,7 +22,7 @@
#include <gtsam/slam/PriorFactor.h> #include <gtsam/slam/PriorFactor.h>
#include <gtsam/slam/BetweenFactor.h> #include <gtsam/slam/BetweenFactor.h>
#include <gtsam/nonlinear/Values-inl.h> #include <gtsam/nonlinear/Values.h>
#include <gtsam/nonlinear/Ordering.h> #include <gtsam/nonlinear/Ordering.h>
#include <gtsam/nonlinear/Key.h> #include <gtsam/nonlinear/Key.h>
#include <gtsam/linear/GaussianSequentialSolver.h> #include <gtsam/linear/GaussianSequentialSolver.h>

View File

@ -18,29 +18,6 @@
#pragma once #pragma once
#include <gtsam/nonlinear/Values-inl.h>
#include <gtsam/nonlinear/TupleValues.h>
// TupleValues instantiations for N = 1-6
#define INSTANTIATE_TUPLE_VALUES1(Values1) \
template class TupleValues1<Values1>;
#define INSTANTIATE_TUPLE_VALUES2(Values1, Values2) \
template class TupleValues2<Values1, Values2>;
#define INSTANTIATE_TUPLE_VALUES3(Values1, Values2, Values3) \
template class TupleValues3<Values1, Values2, Values3>;
#define INSTANTIATE_TUPLE_VALUES4(Values1, Values2, Values3, Values4) \
template class TupleValues4<Values1, Values2, Values3, Values4>;
#define INSTANTIATE_TUPLE_VALUES5(Values1, Values2, Values3, Values4, Values5) \
template class TupleValues5<Values1, Values2, Values3, Values4, Values5>;
#define INSTANTIATE_TUPLE_VALUES6(Values1, Values2, Values3, Values4, Values5, Values6) \
template class TupleValues6<Values1, Values2, Values3, Values4, Values5, Values6>;
namespace gtsam { namespace gtsam {
/* ************************************************************************* */ /* ************************************************************************* */

View File

@ -520,3 +520,5 @@ namespace gtsam {
}; };
} }
#include <gtsam/nonlinear/TupleValues-inl.h>

View File

@ -28,10 +28,6 @@
#include <gtsam/base/Lie-inl.h> #include <gtsam/base/Lie-inl.h>
#include <gtsam/nonlinear/Ordering.h> #include <gtsam/nonlinear/Ordering.h>
#include <gtsam/nonlinear/Values.h>
#define INSTANTIATE_VALUES(J) template class Values<J>;
using namespace std; using namespace std;
namespace gtsam { namespace gtsam {

View File

@ -229,5 +229,7 @@ namespace gtsam {
} }
}; };
} } // \namespace gtsam
#include <gtsam/nonlinear/Values-inl.h>

View File

@ -22,7 +22,7 @@ using namespace boost::assign;
#include <gtsam/base/Testable.h> #include <gtsam/base/Testable.h>
#include <gtsam/base/LieVector.h> #include <gtsam/base/LieVector.h>
#include <gtsam/nonlinear/Values-inl.h> #include <gtsam/nonlinear/Values.h>
using namespace gtsam; using namespace gtsam;
using namespace std; using namespace std;

View File

@ -16,17 +16,9 @@
**/ **/
#include <gtsam/slam/Simulated3D.h> #include <gtsam/slam/Simulated3D.h>
#include <gtsam/nonlinear/Values-inl.h>
#include <gtsam/nonlinear/TupleValues-inl.h>
namespace gtsam { namespace gtsam {
INSTANTIATE_VALUES(simulated3D::PointKey)
INSTANTIATE_VALUES(simulated3D::PoseKey)
using namespace simulated3D;
INSTANTIATE_TUPLE_VALUES2(PoseValues, PointValues)
namespace simulated3D { namespace simulated3D {
Point3 prior (const Point3& x, boost::optional<Matrix&> H) { Point3 prior (const Point3& x, boost::optional<Matrix&> H) {

View File

@ -19,13 +19,10 @@
#include <gtsam/nonlinear/NonlinearFactorGraph-inl.h> #include <gtsam/nonlinear/NonlinearFactorGraph-inl.h>
#include <gtsam/nonlinear/NonlinearOptimizer-inl.h> #include <gtsam/nonlinear/NonlinearOptimizer-inl.h>
#include <gtsam/nonlinear/NonlinearOptimization-inl.h> #include <gtsam/nonlinear/NonlinearOptimization-inl.h>
#include <gtsam/nonlinear/TupleValues-inl.h>
// Use planarSLAM namespace for specific SLAM instance // Use planarSLAM namespace for specific SLAM instance
namespace gtsam { namespace gtsam {
INSTANTIATE_VALUES(planarSLAM::PointKey)
INSTANTIATE_TUPLE_VALUES2(planarSLAM::PoseValues, planarSLAM::PointValues)
INSTANTIATE_NONLINEAR_FACTOR_GRAPH(planarSLAM::Values) INSTANTIATE_NONLINEAR_FACTOR_GRAPH(planarSLAM::Values)
INSTANTIATE_NONLINEAR_OPTIMIZER(planarSLAM::Graph, planarSLAM::Values) INSTANTIATE_NONLINEAR_OPTIMIZER(planarSLAM::Graph, planarSLAM::Values)

View File

@ -16,14 +16,12 @@
**/ **/
#include <gtsam/slam/pose2SLAM.h> #include <gtsam/slam/pose2SLAM.h>
#include <gtsam/nonlinear/Values-inl.h>
#include <gtsam/nonlinear/NonlinearFactorGraph-inl.h> #include <gtsam/nonlinear/NonlinearFactorGraph-inl.h>
#include <gtsam/nonlinear/NonlinearOptimizer-inl.h> #include <gtsam/nonlinear/NonlinearOptimizer-inl.h>
// Use pose2SLAM namespace for specific SLAM instance // Use pose2SLAM namespace for specific SLAM instance
namespace gtsam { namespace gtsam {
INSTANTIATE_VALUES(pose2SLAM::Key)
INSTANTIATE_NONLINEAR_FACTOR_GRAPH(pose2SLAM::Values) INSTANTIATE_NONLINEAR_FACTOR_GRAPH(pose2SLAM::Values)
INSTANTIATE_NONLINEAR_OPTIMIZER(pose2SLAM::Graph, pose2SLAM::Values) INSTANTIATE_NONLINEAR_OPTIMIZER(pose2SLAM::Graph, pose2SLAM::Values)
template class NonlinearOptimizer<pose2SLAM::Graph, pose2SLAM::Values, GaussianFactorGraph, GaussianSequentialSolver>; template class NonlinearOptimizer<pose2SLAM::Graph, pose2SLAM::Values, GaussianFactorGraph, GaussianSequentialSolver>;

View File

@ -16,14 +16,12 @@
**/ **/
#include <gtsam/slam/pose3SLAM.h> #include <gtsam/slam/pose3SLAM.h>
#include <gtsam/nonlinear/Values-inl.h>
#include <gtsam/nonlinear/NonlinearFactorGraph-inl.h> #include <gtsam/nonlinear/NonlinearFactorGraph-inl.h>
#include <gtsam/nonlinear/NonlinearOptimizer-inl.h> #include <gtsam/nonlinear/NonlinearOptimizer-inl.h>
// Use pose3SLAM namespace for specific SLAM instance // Use pose3SLAM namespace for specific SLAM instance
namespace gtsam { namespace gtsam {
INSTANTIATE_VALUES(pose3SLAM::Key)
INSTANTIATE_NONLINEAR_FACTOR_GRAPH(pose3SLAM::Values) INSTANTIATE_NONLINEAR_FACTOR_GRAPH(pose3SLAM::Values)
INSTANTIATE_NONLINEAR_OPTIMIZER(pose3SLAM::Graph, pose3SLAM::Values) INSTANTIATE_NONLINEAR_OPTIMIZER(pose3SLAM::Graph, pose3SLAM::Values)

View File

@ -16,17 +16,9 @@
*/ */
#include <gtsam/slam/simulated2D.h> #include <gtsam/slam/simulated2D.h>
#include <gtsam/nonlinear/Values-inl.h>
#include <gtsam/nonlinear/TupleValues-inl.h>
namespace gtsam { namespace gtsam {
INSTANTIATE_VALUES(simulated2D::PoseKey)
using namespace simulated2D;
INSTANTIATE_TUPLE_VALUES2(PoseValues, PointValues)
namespace simulated2D { namespace simulated2D {
static Matrix I = gtsam::eye(2); static Matrix I = gtsam::eye(2);

View File

@ -16,13 +16,9 @@
*/ */
#include <gtsam/slam/simulated2DOriented.h> #include <gtsam/slam/simulated2DOriented.h>
#include <gtsam/nonlinear/TupleValues-inl.h>
namespace gtsam { namespace gtsam {
using namespace simulated2DOriented;
namespace simulated2DOriented { namespace simulated2DOriented {
static Matrix I = gtsam::eye(3); static Matrix I = gtsam::eye(3);

View File

@ -34,7 +34,6 @@ using namespace std;
// template definitions // template definitions
#include <gtsam/inference/FactorGraph-inl.h> #include <gtsam/inference/FactorGraph-inl.h>
#include <gtsam/nonlinear/Ordering.h> #include <gtsam/nonlinear/Ordering.h>
#include <gtsam/nonlinear/TupleValues-inl.h>
#include <gtsam/nonlinear/NonlinearFactorGraph-inl.h> #include <gtsam/nonlinear/NonlinearFactorGraph-inl.h>
namespace gtsam { namespace gtsam {

View File

@ -20,7 +20,7 @@ using namespace boost;
#include <gtsam/nonlinear/NonlinearOptimizer-inl.h> #include <gtsam/nonlinear/NonlinearOptimizer-inl.h>
#include <gtsam/inference/graph-inl.h> #include <gtsam/inference/graph-inl.h>
#include <gtsam/linear/VectorValues.h> #include <gtsam/linear/VectorValues.h>
#include <gtsam/nonlinear/TupleValues-inl.h> #include <gtsam/nonlinear/TupleValues.h>
#include <gtsam/nonlinear/NonlinearEquality.h> #include <gtsam/nonlinear/NonlinearEquality.h>
#include <gtsam/geometry/GeneralCameraT.h> #include <gtsam/geometry/GeneralCameraT.h>

View File

@ -20,7 +20,7 @@ using namespace boost;
#include <gtsam/nonlinear/NonlinearOptimizer-inl.h> #include <gtsam/nonlinear/NonlinearOptimizer-inl.h>
#include <gtsam/inference/graph-inl.h> #include <gtsam/inference/graph-inl.h>
#include <gtsam/linear/VectorValues.h> #include <gtsam/linear/VectorValues.h>
#include <gtsam/nonlinear/TupleValues-inl.h> #include <gtsam/nonlinear/TupleValues.h>
#include <gtsam/nonlinear/NonlinearEquality.h> #include <gtsam/nonlinear/NonlinearEquality.h>
#include <gtsam/geometry/GeneralCameraT.h> #include <gtsam/geometry/GeneralCameraT.h>

View File

@ -16,12 +16,11 @@
*/ */
#include <gtsam/slam/visualSLAM.h> #include <gtsam/slam/visualSLAM.h>
#include <gtsam/nonlinear/TupleValues-inl.h>
#include <gtsam/nonlinear/NonlinearOptimizer-inl.h> #include <gtsam/nonlinear/NonlinearOptimizer-inl.h>
#include <gtsam/nonlinear/NonlinearFactorGraph-inl.h> #include <gtsam/nonlinear/NonlinearFactorGraph-inl.h>
namespace gtsam { namespace gtsam {
INSTANTIATE_TUPLE_VALUES2(visualSLAM::PoseValues, visualSLAM::PointValues)
INSTANTIATE_NONLINEAR_FACTOR_GRAPH(visualSLAM::Values) INSTANTIATE_NONLINEAR_FACTOR_GRAPH(visualSLAM::Values)
INSTANTIATE_NONLINEAR_OPTIMIZER(visualSLAM::Graph, visualSLAM::Values) INSTANTIATE_NONLINEAR_OPTIMIZER(visualSLAM::Graph, visualSLAM::Values)

View File

@ -20,7 +20,7 @@
#include <gtsam/slam/BetweenFactor.h> #include <gtsam/slam/BetweenFactor.h>
#include <gtsam/nonlinear/ExtendedKalmanFilter-inl.h> #include <gtsam/nonlinear/ExtendedKalmanFilter-inl.h>
#include <gtsam/nonlinear/NonlinearFactor.h> #include <gtsam/nonlinear/NonlinearFactor.h>
#include <gtsam/nonlinear/Values-inl.h> #include <gtsam/nonlinear/Values.h>
#include <gtsam/geometry/Point2.h> #include <gtsam/geometry/Point2.h>
using namespace gtsam; using namespace gtsam;

View File

@ -27,7 +27,6 @@ using namespace boost::assign;
#define GTSAM_MAGIC_GAUSSIAN 3 #define GTSAM_MAGIC_GAUSSIAN 3
#include <gtsam/slam/pose2SLAM.h> #include <gtsam/slam/pose2SLAM.h>
#include <gtsam/nonlinear/TupleValues-inl.h>
#include <gtsam/inference/graph-inl.h> #include <gtsam/inference/graph-inl.h>
#include <gtsam/inference/FactorGraph-inl.h> #include <gtsam/inference/FactorGraph-inl.h>

View File

@ -24,8 +24,6 @@
#include <gtsam/nonlinear/NonlinearFactorGraph.h> #include <gtsam/nonlinear/NonlinearFactorGraph.h>
#include <gtsam/nonlinear/NonlinearOptimizer-inl.h> #include <gtsam/nonlinear/NonlinearOptimizer-inl.h>
#include <gtsam/nonlinear/Values-inl.h>
using namespace std; using namespace std;
using namespace gtsam; using namespace gtsam;

View File

@ -35,7 +35,6 @@
#include <gtsam/slam/simulated2D.h> #include <gtsam/slam/simulated2D.h>
#include <gtsam/linear/GaussianFactor.h> #include <gtsam/linear/GaussianFactor.h>
#include <gtsam/nonlinear/NonlinearFactorGraph-inl.h> #include <gtsam/nonlinear/NonlinearFactorGraph-inl.h>
#include <gtsam/nonlinear/Values-inl.h>
using namespace std; using namespace std;
using namespace gtsam; using namespace gtsam;

View File

@ -23,7 +23,7 @@
#include <gtsam/geometry/Point3.h> #include <gtsam/geometry/Point3.h>
#include <gtsam/geometry/Rot3Q.h> #include <gtsam/geometry/Rot3Q.h>
#include <gtsam/nonlinear/NonlinearFactorGraph-inl.h> #include <gtsam/nonlinear/NonlinearFactorGraph-inl.h>
#include <gtsam/nonlinear/Values-inl.h> #include <gtsam/nonlinear/Values.h>
#include <gtsam/nonlinear/NonlinearOptimization-inl.h> #include <gtsam/nonlinear/NonlinearOptimization-inl.h>
#include <gtsam/slam/BetweenFactor.h> #include <gtsam/slam/BetweenFactor.h>
#include <gtsam/slam/PriorFactor.h> #include <gtsam/slam/PriorFactor.h>

View File

@ -30,7 +30,7 @@
#include <gtsam/base/Vector.h> #include <gtsam/base/Vector.h>
#include <gtsam/nonlinear/Key.h> #include <gtsam/nonlinear/Key.h>
#include <gtsam/nonlinear/TupleValues-inl.h> #include <gtsam/nonlinear/TupleValues.h>
using namespace gtsam; using namespace gtsam;
using namespace std; using namespace std;