Removed extraneous headers that were previously needed for wrap, added start of simulated2D and simulated2DOriented domains to gtsam.h, more wrap documentation

release/4.3a0
Alex Cunningham 2011-12-09 16:36:50 +00:00
parent c302a50146
commit 4e5a80aa56
16 changed files with 110 additions and 355 deletions

101
gtsam.h
View File

@ -13,6 +13,9 @@
* - void * - void
* - Any class with which be copied with boost::make_shared() * - Any class with which be copied with boost::make_shared()
* - boost::shared_ptr of any object type * - boost::shared_ptr of any object type
* Limitations on methods
* - Parsing does not support overloading
* - There can only be one method with a given name
* Arguments to functions any of * Arguments to functions any of
* - Eigen types: Matrix, Vector * - Eigen types: Matrix, Vector
* - Eigen types and classes as an optionally const reference * - Eigen types and classes as an optionally const reference
@ -31,6 +34,9 @@
* - In each case, the namespace must be fully specified, e.g., "namespace1::namespace2::ClassName" * - In each case, the namespace must be fully specified, e.g., "namespace1::namespace2::ClassName"
* Methods must start with a lowercase letter * Methods must start with a lowercase letter
* Static methods must start with a letter (upper or lowercase) and use the "static" keyword * Static methods must start with a letter (upper or lowercase) and use the "static" keyword
* Includes in C++ wrappers
* - By default, the include will be <[classname].h>
* - To override, add a full include statement inside the class definition
*/ */
/** /**
@ -181,6 +187,12 @@ class SharedDiagonal {
Vector sample() const; Vector sample() const;
}; };
class SharedNoiseModel {
#include <gtsam/linear/SharedGaussian.h>
SharedNoiseModel(const SharedDiagonal& model);
SharedNoiseModel(const SharedGaussian& model);
};
class VectorValues { class VectorValues {
VectorValues(); VectorValues();
VectorValues(int nVars, int varDim); VectorValues(int nVars, int varDim);
@ -245,6 +257,14 @@ class GaussianFactorGraph {
Matrix sparseJacobian_() const; Matrix sparseJacobian_() const;
}; };
class GaussianSequentialSolver {
GaussianSequentialSolver(const GaussianFactorGraph& graph, bool useQR);
GaussianBayesNet* eliminate() const;
VectorValues* optimize() const;
GaussianFactor* marginalFactor(int j) const;
Matrix marginalCovariance(int j) const;
};
class KalmanFilter { class KalmanFilter {
KalmanFilter(Vector x, const SharedDiagonal& model); KalmanFilter(Vector x, const SharedDiagonal& model);
void print(string s) const; void print(string s) const;
@ -263,11 +283,6 @@ class Ordering {
void push_back(string key); void push_back(string key);
}; };
class SharedNoiseModel {
SharedNoiseModel();
// FIXME: this needs actual constructors
};
// Planar SLAM example domain // Planar SLAM example domain
namespace planarSLAM { namespace planarSLAM {
@ -312,14 +327,51 @@ class Odometry {
}///\namespace planarSLAM }///\namespace planarSLAM
class GaussianSequentialSolver { // Simulated2D Example Domain
GaussianSequentialSolver(const GaussianFactorGraph& graph, bool useQR); namespace simulated2D {
GaussianBayesNet* eliminate() const;
VectorValues* optimize() const; class Values {
GaussianFactor* marginalFactor(int j) const; #include <gtsam/slam/simulated2D.h>
Matrix marginalCovariance(int j) const; Values();
void insertPose(int i, const Point2& p);
void insertPoint(int j, const Point2& p);
int nrPoses() const;
int nrPoints() const;
Point2 pose(int i);
Point2 point(int j);
}; };
class Graph {
#include <gtsam/slam/simulated2D.h>
Graph();
};
// TODO: add factors, etc.
}///\namespace simulated2D
// Simulated2DOriented Example Domain
namespace simulated2DOriented {
class Values {
#include <gtsam/slam/simulated2DOriented.h>
Values();
void insertPose(int i, const Pose2& p);
void insertPoint(int j, const Point2& p);
int nrPoses() const;
int nrPoints() const;
Pose2 pose(int i);
Point2 point(int j);
};
class Graph {
#include <gtsam/slam/simulated2DOriented.h>
Graph();
};
// TODO: add factors, etc.
}///\namespace simulated2DOriented
//// These are considered to be broken and will be added back as they start working //// These are considered to be broken and will be added back as they start working
//// It's assumed that there have been interface changes that might break this //// It's assumed that there have been interface changes that might break this
@ -339,28 +391,6 @@ class GaussianSequentialSolver {
// void push_back(GaussianFactor* factor); // void push_back(GaussianFactor* factor);
//}; //};
// //
//class Simulated2DValues {
// Simulated2DValues();
// void print(string s) const;
// void insertPose(int i, const Point2& p);
// void insertPoint(int j, const Point2& p);
// int nrPoses() const;
// int nrPoints() const;
// Point2* pose(int i);
// Point2* point(int j);
//};
//
//class Simulated2DOrientedValues {
// Simulated2DOrientedValues();
// void print(string s) const;
// void insertPose(int i, const Pose2& p);
// void insertPoint(int j, const Point2& p);
// int nrPoses() const;
// int nrPoints() const;
// Pose2* pose(int i);
// Point2* point(int j);
//};
//
//class Simulated2DPosePrior { //class Simulated2DPosePrior {
// Simulated2DPosePrior(Point2& mu, const SharedDiagonal& model, int i); // Simulated2DPosePrior(Point2& mu, const SharedDiagonal& model, int i);
// void print(string s) const; // void print(string s) const;
@ -397,10 +427,6 @@ class GaussianSequentialSolver {
// double error(const Simulated2DValues& c) const; // double error(const Simulated2DValues& c) const;
//}; //};
// //
//// These are currently broken
//// Solve by parsing a namespace pose2SLAM::Values and making a Pose2SLAMValues class
//// We also have to solve the shared pointer mess to avoid duplicate methods
//
//class GaussianFactor { //class GaussianFactor {
// GaussianFactor(string key1, // GaussianFactor(string key1,
// Matrix A1, // Matrix A1,
@ -435,7 +461,6 @@ class GaussianSequentialSolver {
// VectorValues* conjugateGradientDescent_(const VectorValues& x0) const; // VectorValues* conjugateGradientDescent_(const VectorValues& x0) const;
//}; //};
// //
//
//class Pose2Values{ //class Pose2Values{
// Pose2Values(); // Pose2Values();
// Pose2 get(string key) const; // Pose2 get(string key) const;

View File

@ -15,24 +15,12 @@ headers += simulated2DConstraints.h
sources += simulated2D.cpp smallExample.cpp sources += simulated2D.cpp smallExample.cpp
check_PROGRAMS += tests/testSimulated2D check_PROGRAMS += tests/testSimulated2D
# MATLAB Wrap headers for simulated2D
headers += Simulated2DMeasurement.h
headers += Simulated2DOdometry.h
headers += Simulated2DPointPrior.h
headers += Simulated2DPosePrior.h
headers += Simulated2DValues.h
# simulated2DOriented example # simulated2DOriented example
sources += simulated2DOriented.cpp sources += simulated2DOriented.cpp
check_PROGRAMS += tests/testSimulated2DOriented check_PROGRAMS += tests/testSimulated2DOriented
# MATLAB Wrap headers for simulated2DOriented
headers += Simulated2DOrientedOdometry.h
headers += Simulated2DOrientedPosePrior.h
headers += Simulated2DOrientedValues.h
# simulated3D example # simulated3D example
sources += Simulated3D.cpp sources += simulated3D.cpp
check_PROGRAMS += tests/testSimulated3D check_PROGRAMS += tests/testSimulated3D
# Generic SLAM headers # Generic SLAM headers
@ -50,12 +38,6 @@ check_PROGRAMS += tests/testPose2SLAM
sources += planarSLAM.cpp sources += planarSLAM.cpp
check_PROGRAMS += tests/testPlanarSLAM check_PROGRAMS += tests/testPlanarSLAM
# MATLAB Wrap headers for planarSLAM
# headers += Landmark2.h
# headers += PlanarSLAMGraph.h
# headers += PlanarSLAMValues.h
# headers += PlanarSLAMOdometry.h
# 3D Pose constraints # 3D Pose constraints
sources += pose3SLAM.cpp sources += pose3SLAM.cpp
check_PROGRAMS += tests/testPose3SLAM check_PROGRAMS += tests/testPose3SLAM

View File

@ -1,28 +0,0 @@
/* ----------------------------------------------------------------------------
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
* Atlanta, Georgia 30332-0415
* All Rights Reserved
* Authors: Frank Dellaert, et al. (see THANKS for the full author list)
* See LICENSE for the license information
* -------------------------------------------------------------------------- */
/**
* @file Simulated2DMeasurement.h
* @brief Re-created on Feb 22, 2010 for compatibility with MATLAB
* @author Frank Dellaert
*/
#pragma once
#include <gtsam/slam/simulated2D.h>
#include <gtsam/slam/Simulated2DValues.h>
namespace gtsam {
typedef simulated2D::Measurement Simulated2DMeasurement;
}

View File

@ -1,28 +0,0 @@
/* ----------------------------------------------------------------------------
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
* Atlanta, Georgia 30332-0415
* All Rights Reserved
* Authors: Frank Dellaert, et al. (see THANKS for the full author list)
* See LICENSE for the license information
* -------------------------------------------------------------------------- */
/**
* @file Simulated2DOdometry.h
* @brief Re-created on Feb 22, 2010 for compatibility with MATLAB
* @author Frank Dellaert
*/
#pragma once
#include <gtsam/slam/simulated2D.h>
#include <gtsam/slam/Simulated2DValues.h>
namespace gtsam {
typedef simulated2D::Odometry Simulated2DOdometry;
}

View File

@ -1,28 +0,0 @@
/* ----------------------------------------------------------------------------
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
* Atlanta, Georgia 30332-0415
* All Rights Reserved
* Authors: Frank Dellaert, et al. (see THANKS for the full author list)
* See LICENSE for the license information
* -------------------------------------------------------------------------- */
/**
* @file Simulated2DOrientedOdometry.h
* @brief Re-created on Feb 22, 2010 for compatibility with MATLAB
* @author Kai Ni
*/
#pragma once
#include <gtsam/slam/simulated2DOriented.h>
#include <gtsam/slam/Simulated2DOrientedValues.h>
namespace gtsam {
typedef simulated2DOriented::Odometry Simulated2DOrientedOdometry;
}

View File

@ -1,29 +0,0 @@
/* ----------------------------------------------------------------------------
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
* Atlanta, Georgia 30332-0415
* All Rights Reserved
* Authors: Frank Dellaert, et al. (see THANKS for the full author list)
* See LICENSE for the license information
* -------------------------------------------------------------------------- */
/**
* @file Simulated2DOrientedPosePrior.h
* @brief Re-created on Feb 22, 2010 for compatibility with MATLAB
* @author Kai Ni
*/
#pragma once
#include <gtsam/slam/simulated2DOriented.h>
#include <gtsam/slam/Simulated2DOrientedValues.h>
namespace gtsam {
/** Create a prior on a pose Point2 with key 'x1' etc... */
typedef simulated2DOriented::GenericPosePrior<Simulated2DOrientedValues, simulated2DOriented::PoseKey> Simulated2DOrientedPosePrior;
}

View File

@ -1,59 +0,0 @@
/* ----------------------------------------------------------------------------
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
* Atlanta, Georgia 30332-0415
* All Rights Reserved
* Authors: Frank Dellaert, et al. (see THANKS for the full author list)
* See LICENSE for the license information
* -------------------------------------------------------------------------- */
/**
* @file Simulated2DValues.h
* @brief Re-created on Feb 22, 2010 for compatibility with MATLAB
* @author Frank Dellaert
*/
#pragma once
#include <gtsam/slam/simulated2DOriented.h>
namespace gtsam {
class Simulated2DOrientedValues: public simulated2DOriented::Values {
public:
typedef boost::shared_ptr<Point2> sharedPoint;
typedef boost::shared_ptr<Pose2> sharedPose;
Simulated2DOrientedValues() {
}
void insertPose(const simulated2DOriented::PoseKey& i, const Pose2& p) {
insert(i, p);
}
void insertPoint(const simulated2DOriented::PointKey& j, const Point2& p) {
insert(j, p);
}
int nrPoses() const {
return this->first_.size();
}
int nrPoints() const {
return this->second_.size();
}
sharedPose pose(const simulated2DOriented::PoseKey& i) {
return sharedPose(new Pose2((*this)[i]));
}
sharedPoint point(const simulated2DOriented::PointKey& j) {
return sharedPoint(new Point2((*this)[j]));
}
};
} // namespace gtsam

View File

@ -1,29 +0,0 @@
/* ----------------------------------------------------------------------------
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
* Atlanta, Georgia 30332-0415
* All Rights Reserved
* Authors: Frank Dellaert, et al. (see THANKS for the full author list)
* See LICENSE for the license information
* -------------------------------------------------------------------------- */
/**
* @file Simulated2DPointPrior.h
* @brief Re-created on Feb 22, 2010 for compatibility with MATLAB
* @author Frank Dellaert
*/
#pragma once
#include <gtsam/slam/simulated2D.h>
#include <gtsam/slam/Simulated2DValues.h>
namespace gtsam {
/** Create a prior on a landmark Point2 with key 'l1' etc... */
typedef simulated2D::GenericPrior<Simulated2DValues, simulated2D::PointKey> Simulated2DPointPrior;
}

View File

@ -1,29 +0,0 @@
/* ----------------------------------------------------------------------------
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
* Atlanta, Georgia 30332-0415
* All Rights Reserved
* Authors: Frank Dellaert, et al. (see THANKS for the full author list)
* See LICENSE for the license information
* -------------------------------------------------------------------------- */
/**
* @file Simulated2DPosePrior.h
* @brief Re-created on Feb 22, 2010 for compatibility with MATLAB
* @author Frank Dellaert
*/
#pragma once
#include <gtsam/slam/simulated2D.h>
#include <gtsam/slam/Simulated2DValues.h>
namespace gtsam {
/** Create a prior on a pose Point2 with key 'x1' etc... */
typedef simulated2D::GenericPrior<Simulated2DValues, simulated2D::PoseKey> Simulated2DPosePrior;
}

View File

@ -1,58 +0,0 @@
/* ----------------------------------------------------------------------------
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
* Atlanta, Georgia 30332-0415
* All Rights Reserved
* Authors: Frank Dellaert, et al. (see THANKS for the full author list)
* See LICENSE for the license information
* -------------------------------------------------------------------------- */
/**
* @file Simulated2DValues.h
* @brief Re-created on Feb 22, 2010 for compatibility with MATLAB
* @author Frank Dellaert
*/
#pragma once
#include <gtsam/slam/simulated2D.h>
namespace gtsam {
class Simulated2DValues: public simulated2D::Values {
public:
typedef boost::shared_ptr<Point2> sharedPoint;
Simulated2DValues() {
}
void insertPose(const simulated2D::PoseKey& i, const Point2& p) {
insert(i, p);
}
void insertPoint(const simulated2D::PointKey& j, const Point2& p) {
insert(j, p);
}
int nrPoses() const {
return this->first_.size();
}
int nrPoints() const {
return this->second_.size();
}
sharedPoint pose(const simulated2D::PoseKey& i) {
return sharedPoint(new Point2((*this)[i]));
}
sharedPoint point(const simulated2D::PointKey& j) {
return sharedPoint(new Point2((*this)[j]));
}
};
} // namespace gtsam

View File

@ -21,6 +21,7 @@
#include <gtsam/geometry/Point2.h> #include <gtsam/geometry/Point2.h>
#include <gtsam/nonlinear/TupleValues.h> #include <gtsam/nonlinear/TupleValues.h>
#include <gtsam/nonlinear/NonlinearFactor.h> #include <gtsam/nonlinear/NonlinearFactor.h>
#include <gtsam/nonlinear/NonlinearFactorGraph.h>
// \namespace // \namespace
@ -72,13 +73,13 @@ namespace gtsam {
} }
/// Return pose i /// Return pose i
sharedPoint pose(const simulated2D::PoseKey& i) { Point2 pose(const simulated2D::PoseKey& i) const {
return sharedPoint(new Point2((*this)[i])); return (*this)[i];
} }
/// Return point j /// Return point j
sharedPoint point(const simulated2D::PointKey& j) { Point2 point(const simulated2D::PointKey& j) const {
return sharedPoint(new Point2((*this)[j])); return (*this)[j];
} }
}; };
@ -232,5 +233,12 @@ namespace gtsam {
typedef GenericOdometry<Values, PoseKey> Odometry; typedef GenericOdometry<Values, PoseKey> Odometry;
typedef GenericMeasurement<Values, PoseKey, PointKey> Measurement; typedef GenericMeasurement<Values, PoseKey, PointKey> Measurement;
// Specialization of a graph for this example domain
// TODO: add functions to add factor types
class Graph : public NonlinearFactorGraph<Values> {
public:
Graph() {}
};
} // namespace simulated2D } // namespace simulated2D
} // namespace gtsam } // namespace gtsam

View File

@ -21,6 +21,7 @@
#include <gtsam/geometry/Pose2.h> #include <gtsam/geometry/Pose2.h>
#include <gtsam/nonlinear/TupleValues.h> #include <gtsam/nonlinear/TupleValues.h>
#include <gtsam/nonlinear/NonlinearFactor.h> #include <gtsam/nonlinear/NonlinearFactor.h>
#include <gtsam/nonlinear/NonlinearFactorGraph.h>
// \namespace // \namespace
@ -33,7 +34,27 @@ namespace gtsam {
typedef TypedSymbol<Pose2, 'x'> PoseKey; typedef TypedSymbol<Pose2, 'x'> PoseKey;
typedef Values<PoseKey> PoseValues; typedef Values<PoseKey> PoseValues;
typedef Values<PointKey> PointValues; typedef Values<PointKey> PointValues;
typedef TupleValues2<PoseValues, PointValues> Values;
/// Specialized Values structure with syntactic sugar for
/// compatibility with matlab
class Values: public TupleValues2<PoseValues, PointValues> {
public:
Values() {}
void insertPose(const PoseKey& i, const Pose2& p) {
insert(i, p);
}
void insertPoint(const PointKey& j, const Point2& p) {
insert(j, p);
}
int nrPoses() const { return this->first_.size(); }
int nrPoints() const { return this->second_.size(); }
Pose2 pose(const PoseKey& i) const { return (*this)[i]; }
Point2 point(const PointKey& j) const { return (*this)[j]; }
};
//TODO:: point prior is not implemented right now //TODO:: point prior is not implemented right now
@ -100,5 +121,12 @@ namespace gtsam {
typedef GenericOdometry<Values, PoseKey> Odometry; typedef GenericOdometry<Values, PoseKey> Odometry;
/// Graph specialization for syntactic sugar use with matlab
class Graph : public NonlinearFactorGraph<Values> {
public:
Graph() {}
// TODO: add functions to add factors
};
} // namespace simulated2DOriented } // namespace simulated2DOriented
} // namespace gtsam } // namespace gtsam

View File

@ -15,7 +15,7 @@
* @author Alex Cunningham * @author Alex Cunningham
**/ **/
#include <gtsam/slam/Simulated3D.h> #include <gtsam/slam/simulated3D.h>
namespace gtsam { namespace gtsam {

View File

@ -21,7 +21,7 @@
#include <gtsam/base/Testable.h> #include <gtsam/base/Testable.h>
#include <gtsam/base/numericalDerivative.h> #include <gtsam/base/numericalDerivative.h>
#include <gtsam/geometry/Pose3.h> #include <gtsam/geometry/Pose3.h>
#include <gtsam/slam/Simulated3D.h> #include <gtsam/slam/simulated3D.h>
using namespace gtsam; using namespace gtsam;

View File

@ -91,16 +91,16 @@ generate_toolbox: $(top_srcdir)/gtsam.h
source_mode = -m 644 source_mode = -m 644
wrap-install-matlab-toolbox: wrap-install-matlab-toolbox: generate_toolbox
install -d ${toolbox}/gtsam install -d ${toolbox}/gtsam
install ${source_mode} -c ../toolbox/*.m ${toolbox}/gtsam install ${source_mode} -c ../toolbox/*.m ${toolbox}/gtsam
install ${source_mode} -c ../toolbox/*.cpp ${toolbox}/gtsam install ${source_mode} -c ../toolbox/*.cpp ${toolbox}/gtsam
install ${source_mode} -c ../toolbox/Makefile ${toolbox}/gtsam install ${source_mode} -c ../toolbox/Makefile ${toolbox}/gtsam
cp -ru ../toolbox/@* ${toolbox}/gtsam cp -ru ../toolbox/@* ${toolbox}/gtsam
wrap-install-bin: wrap-install-bin: wrap
install -d ${wrap} install -d ${wrap}
install ./wrap ${wrap} install -c ./wrap ${wrap}
wrap-install-matlab-tests: wrap-install-matlab-tests:
install -d ${toolbox}/gtsam/tests install -d ${toolbox}/gtsam/tests