| 
									
										
										
										
											2011-12-02 06:06:03 +08:00
										 |  |  | /**
 | 
					
						
							| 
									
										
										
										
											2011-12-07 11:05:37 +08:00
										 |  |  |  * GTSAM Wrap Module Definition | 
					
						
							| 
									
										
										
										
											2011-12-02 06:06:03 +08:00
										 |  |  |  * | 
					
						
							|  |  |  |  * These are the current classes available through the matlab toolbox interface, | 
					
						
							|  |  |  |  * add more functions/classes as they are available. | 
					
						
							|  |  |  |  * | 
					
						
							|  |  |  |  * Requirements: | 
					
						
							| 
									
										
										
										
											2011-12-07 11:05:37 +08:00
										 |  |  |  *   Classes must start with an uppercase letter | 
					
						
							|  |  |  |  *   Only one Method/Constructor per line | 
					
						
							|  |  |  |  *   Methods can return | 
					
						
							|  |  |  |  *     - Eigen types:       Matrix, Vector | 
					
						
							|  |  |  |  *     - C/C++ basic types: string, bool, size_t, int, double | 
					
						
							|  |  |  |  *     - void | 
					
						
							|  |  |  |  *     - Any class with which be copied with boost::make_shared() | 
					
						
							|  |  |  |  *     - boost::shared_ptr of any object type | 
					
						
							| 
									
										
										
										
											2011-12-10 00:36:50 +08:00
										 |  |  |  *   Limitations on methods | 
					
						
							|  |  |  |  *     - Parsing does not support overloading | 
					
						
							|  |  |  |  *     - There can only be one method with a given name | 
					
						
							| 
									
										
										
										
											2011-12-07 11:05:37 +08:00
										 |  |  |  *   Arguments to functions any of | 
					
						
							|  |  |  |  *   	 - Eigen types:       Matrix, Vector | 
					
						
							|  |  |  |  *   	 - Eigen types and classes as an optionally const reference | 
					
						
							|  |  |  |  *     - C/C++ basic types: string, bool, size_t, int, double | 
					
						
							|  |  |  |  *     - Any class with which be copied with boost::make_shared() (except Eigen) | 
					
						
							|  |  |  |  *     - boost::shared_ptr of any object type (except Eigen) | 
					
						
							|  |  |  |  *   Comments can use either C++ or C style, with multiple lines | 
					
						
							| 
									
										
										
										
											2011-12-09 04:58:06 +08:00
										 |  |  |  *   Namespace definitions | 
					
						
							|  |  |  |  *     - Names of namespaces must start with a lowercase letter | 
					
						
							|  |  |  |  *   	 - start a namespace with "namespace {" | 
					
						
							|  |  |  |  *   	 - end a namespace with exactly "}///\namespace [namespace_name]", optionally adding the name of the namespace | 
					
						
							|  |  |  |  *   	 - This ending is not C++ standard, and must contain "}///\namespace" to parse | 
					
						
							|  |  |  |  *   	 - Namespaces can be nested | 
					
						
							|  |  |  |  *   Namespace usage | 
					
						
							|  |  |  |  *   	 - Namespaces can be specified for classes in arguments and return values | 
					
						
							|  |  |  |  *   	 - In each case, the namespace must be fully specified, e.g., "namespace1::namespace2::ClassName" | 
					
						
							| 
									
										
										
										
											2011-12-02 06:06:03 +08:00
										 |  |  |  *   Methods must start with a lowercase letter | 
					
						
							| 
									
										
										
										
											2011-12-07 11:05:30 +08:00
										 |  |  |  *   Static methods must start with a letter (upper or lowercase) and use the "static" keyword | 
					
						
							| 
									
										
										
										
											2011-12-10 00:36:50 +08:00
										 |  |  |  *   Includes in C++ wrappers | 
					
						
							|  |  |  |  *   	 - By default, the include will be <[classname].h> | 
					
						
							| 
									
										
										
										
											2011-12-16 03:39:14 +08:00
										 |  |  |  *   	 - All namespaces must have angle brackets: <path> | 
					
						
							|  |  |  |  *   	 - To override, add a full include statement just before the class statement | 
					
						
							|  |  |  |  *   	 - An override include can be added for a namespace by placing it just before the namespace statement | 
					
						
							|  |  |  |  *   	 - Both classes and namespace accept exactly one namespace | 
					
						
							| 
									
										
										
										
											2011-12-16 05:27:08 +08:00
										 |  |  |  *   Overriding type dependency checks | 
					
						
							|  |  |  |  *     - If you are using a class 'OtherClass' not wrapped in this definition file, add "class OtherClass;" to avoid a dependency error | 
					
						
							|  |  |  |  *     - Limitation: this only works if the class does not need a namespace specification | 
					
						
							| 
									
										
										
										
											2011-12-07 11:05:37 +08:00
										 |  |  |  */ | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /**
 | 
					
						
							|  |  |  |  * Status: | 
					
						
							|  |  |  |  *  - TODO: global functions | 
					
						
							| 
									
										
										
										
											2011-12-07 23:23:20 +08:00
										 |  |  |  *  - TODO: default values for arguments | 
					
						
							|  |  |  |  *  - TODO: overloaded functions | 
					
						
							| 
									
										
										
										
											2011-12-16 05:23:20 +08:00
										 |  |  |  *  - TODO: signatures for constructors can be ambiguous if two types have the same first letter | 
					
						
							| 
									
										
										
										
											2011-12-07 23:23:20 +08:00
										 |  |  |  *  - TODO: Handle Rot3M conversions to quaternions | 
					
						
							| 
									
										
										
										
											2011-12-02 06:06:03 +08:00
										 |  |  |  */ | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2011-12-10 04:29:47 +08:00
										 |  |  | // Everything is in the gtsam namespace, so we avoid copying everything in
 | 
					
						
							|  |  |  | using namespace gtsam; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2011-10-14 02:41:56 +08:00
										 |  |  | class Point2 { | 
					
						
							| 
									
										
										
										
											2011-10-21 13:07:35 +08:00
										 |  |  | 	Point2(); | 
					
						
							|  |  |  | 	Point2(double x, double y); | 
					
						
							| 
									
										
										
										
											2011-12-07 11:05:37 +08:00
										 |  |  | 	static Point2 Expmap(Vector v); | 
					
						
							| 
									
										
										
										
											2011-12-02 10:32:18 +08:00
										 |  |  | 	static Vector Logmap(const Point2& p); | 
					
						
							| 
									
										
										
										
											2011-10-21 13:07:35 +08:00
										 |  |  | 	void print(string s) const; | 
					
						
							|  |  |  | 	double x(); | 
					
						
							|  |  |  | 	double y(); | 
					
						
							| 
									
										
										
										
											2011-12-07 11:05:37 +08:00
										 |  |  | 	Vector localCoordinates(const Point2& p); | 
					
						
							|  |  |  | 	Point2 compose(const Point2& p2); | 
					
						
							|  |  |  | 	Point2 between(const Point2& p2); | 
					
						
							|  |  |  | 	Point2 retract(Vector v); | 
					
						
							| 
									
										
										
										
											2011-10-14 02:41:56 +08:00
										 |  |  | }; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | class Point3 { | 
					
						
							| 
									
										
										
										
											2011-10-21 13:07:35 +08:00
										 |  |  | 	Point3(); | 
					
						
							|  |  |  | 	Point3(double x, double y, double z); | 
					
						
							|  |  |  | 	Point3(Vector v); | 
					
						
							| 
									
										
										
										
											2011-12-07 11:05:37 +08:00
										 |  |  | 	static Point3 Expmap(Vector v); | 
					
						
							| 
									
										
										
										
											2011-12-02 10:32:18 +08:00
										 |  |  | 	static Vector Logmap(const Point3& p); | 
					
						
							| 
									
										
										
										
											2011-10-21 13:07:35 +08:00
										 |  |  | 	void print(string s) const; | 
					
						
							| 
									
										
										
										
											2011-12-01 09:59:34 +08:00
										 |  |  | 	bool equals(const Point3& p, double tol); | 
					
						
							| 
									
										
										
										
											2011-10-21 13:07:35 +08:00
										 |  |  | 	Vector vector() const; | 
					
						
							|  |  |  | 	double x(); | 
					
						
							|  |  |  | 	double y(); | 
					
						
							|  |  |  | 	double z(); | 
					
						
							| 
									
										
										
										
											2011-12-07 11:05:37 +08:00
										 |  |  | 	Vector localCoordinates(const Point3& p); | 
					
						
							|  |  |  | 	Point3 retract(Vector v); | 
					
						
							|  |  |  | 	Point3 compose(const Point3& p2); | 
					
						
							|  |  |  | 	Point3 between(const Point3& p2); | 
					
						
							| 
									
										
										
										
											2011-10-21 13:07:35 +08:00
										 |  |  | }; | 
					
						
							| 
									
										
										
										
											2011-10-14 02:41:56 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2011-10-14 12:43:40 +08:00
										 |  |  | class Rot2 { | 
					
						
							|  |  |  | 	Rot2(); | 
					
						
							| 
									
										
										
										
											2011-10-22 00:56:50 +08:00
										 |  |  | 	Rot2(double theta); | 
					
						
							| 
									
										
										
										
											2011-12-07 11:05:37 +08:00
										 |  |  | 	static Rot2 Expmap(Vector v); | 
					
						
							| 
									
										
										
										
											2011-12-02 10:32:18 +08:00
										 |  |  | 	static Vector Logmap(const Rot2& p); | 
					
						
							| 
									
										
										
										
											2011-12-07 23:23:20 +08:00
										 |  |  | 	static Rot2 fromAngle(double theta); | 
					
						
							|  |  |  | 	static Rot2 fromDegrees(double theta); | 
					
						
							|  |  |  | 	static Rot2 fromCosSin(double c, double s); | 
					
						
							|  |  |  | 	static Rot2 relativeBearing(const Point2& d); // Ignoring derivative
 | 
					
						
							|  |  |  | 	static Rot2 atan2(double y, double x); | 
					
						
							| 
									
										
										
										
											2011-10-22 00:56:50 +08:00
										 |  |  | 	void print(string s) const; | 
					
						
							| 
									
										
										
										
											2011-12-01 09:59:34 +08:00
										 |  |  | 	bool equals(const Rot2& rot, double tol) const; | 
					
						
							| 
									
										
										
										
											2011-12-07 23:23:20 +08:00
										 |  |  | 	double theta() const; | 
					
						
							|  |  |  | 	double degrees() const; | 
					
						
							| 
									
										
										
										
											2011-10-22 00:56:50 +08:00
										 |  |  | 	double c() const; | 
					
						
							|  |  |  | 	double s() const; | 
					
						
							| 
									
										
										
										
											2011-12-07 11:05:37 +08:00
										 |  |  | 	Vector localCoordinates(const Rot2& p); | 
					
						
							|  |  |  | 	Rot2 retract(Vector v); | 
					
						
							|  |  |  | 	Rot2 compose(const Rot2& p2); | 
					
						
							|  |  |  | 	Rot2 between(const Rot2& p2); | 
					
						
							| 
									
										
										
										
											2011-10-14 12:43:40 +08:00
										 |  |  | }; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2011-12-01 09:59:34 +08:00
										 |  |  | class Rot3 { | 
					
						
							|  |  |  | 	Rot3(); | 
					
						
							|  |  |  | 	Rot3(Matrix R); | 
					
						
							| 
									
										
										
										
											2011-12-07 11:05:37 +08:00
										 |  |  | 	static Rot3 Expmap(Vector v); | 
					
						
							| 
									
										
										
										
											2011-12-02 10:32:18 +08:00
										 |  |  | 	static Vector Logmap(const Rot3& p); | 
					
						
							| 
									
										
										
										
											2011-12-07 11:05:30 +08:00
										 |  |  |   static Rot3 ypr(double y, double p, double r); | 
					
						
							| 
									
										
										
										
											2011-12-07 23:23:20 +08:00
										 |  |  |   static Rot3 Rx(double t); | 
					
						
							|  |  |  |   static Rot3 Ry(double t); | 
					
						
							|  |  |  |   static Rot3 Rz(double t); | 
					
						
							|  |  |  |   static Rot3 RzRyRx(double x, double y, double z); | 
					
						
							| 
									
										
										
										
											2012-01-05 00:18:38 +08:00
										 |  |  |   static Rot3 RzRyRx(Vector xyz); | 
					
						
							| 
									
										
										
										
											2011-12-07 23:23:20 +08:00
										 |  |  |   static Rot3 yaw  (double t); // positive yaw is to right (as in aircraft heading)
 | 
					
						
							|  |  |  |   static Rot3 pitch(double t); // positive pitch is up (increasing aircraft altitude)
 | 
					
						
							|  |  |  |   static Rot3 roll (double t); // positive roll is to right (increasing yaw in aircraft)
 | 
					
						
							|  |  |  |   static Rot3 quaternion(double w, double x, double y, double z); | 
					
						
							| 
									
										
										
										
											2012-01-05 00:18:38 +08:00
										 |  |  |   static Rot3 rodriguez(Vector v); | 
					
						
							| 
									
										
										
										
											2011-12-02 02:57:32 +08:00
										 |  |  | 	Matrix matrix() const; | 
					
						
							|  |  |  | 	Matrix transpose() const; | 
					
						
							|  |  |  | 	Vector xyz() const; | 
					
						
							|  |  |  | 	Vector ypr() const; | 
					
						
							| 
									
										
										
										
											2011-12-08 00:41:50 +08:00
										 |  |  |   double roll() const; | 
					
						
							|  |  |  |   double pitch() const; | 
					
						
							|  |  |  |   double yaw() const; | 
					
						
							| 
									
										
										
										
											2011-12-07 23:23:20 +08:00
										 |  |  | //  Vector toQuaternion() const;  // FIXME: Can't cast to Vector properly
 | 
					
						
							| 
									
										
										
										
											2011-12-01 09:59:34 +08:00
										 |  |  | 	void print(string s) const; | 
					
						
							|  |  |  | 	bool equals(const Rot3& rot, double tol) const; | 
					
						
							| 
									
										
										
										
											2011-12-07 11:05:37 +08:00
										 |  |  | 	Vector localCoordinates(const Rot3& p); | 
					
						
							|  |  |  | 	Rot3 retract(Vector v); | 
					
						
							|  |  |  | 	Rot3 compose(const Rot3& p2); | 
					
						
							|  |  |  | 	Rot3 between(const Rot3& p2); | 
					
						
							| 
									
										
										
										
											2011-12-01 09:59:34 +08:00
										 |  |  | }; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2011-10-14 02:41:56 +08:00
										 |  |  | class Pose2 { | 
					
						
							| 
									
										
										
										
											2011-10-21 13:07:35 +08:00
										 |  |  | 	Pose2(); | 
					
						
							|  |  |  | 	Pose2(double x, double y, double theta); | 
					
						
							|  |  |  | 	Pose2(double theta, const Point2& t); | 
					
						
							|  |  |  | 	Pose2(const Rot2& r, const Point2& t); | 
					
						
							| 
									
										
										
										
											2011-11-04 14:10:20 +08:00
										 |  |  | 	Pose2(Vector v); | 
					
						
							| 
									
										
										
										
											2011-12-07 11:05:37 +08:00
										 |  |  | 	static Pose2 Expmap(Vector v); | 
					
						
							| 
									
										
										
										
											2011-12-02 10:32:18 +08:00
										 |  |  | 	static Vector Logmap(const Pose2& p); | 
					
						
							| 
									
										
										
										
											2011-10-21 13:07:35 +08:00
										 |  |  | 	void print(string s) const; | 
					
						
							|  |  |  | 	bool equals(const Pose2& pose, double tol) const; | 
					
						
							|  |  |  | 	double x() const; | 
					
						
							|  |  |  | 	double y() const; | 
					
						
							|  |  |  | 	double theta() const; | 
					
						
							| 
									
										
										
										
											2011-11-04 12:27:55 +08:00
										 |  |  | 	int dim() const; | 
					
						
							| 
									
										
										
										
											2011-12-07 11:05:37 +08:00
										 |  |  | 	Vector localCoordinates(const Pose2& p); | 
					
						
							|  |  |  | 	Pose2 retract(Vector v); | 
					
						
							|  |  |  | 	Pose2 compose(const Pose2& p2); | 
					
						
							|  |  |  | 	Pose2 between(const Pose2& p2); | 
					
						
							| 
									
										
										
										
											2011-12-08 00:41:50 +08:00
										 |  |  | 	Rot2 bearing(const Point2& point); | 
					
						
							|  |  |  | 	double range(const Point2& point); | 
					
						
							| 
									
										
										
										
											2011-10-21 13:07:35 +08:00
										 |  |  | }; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2011-12-01 09:59:34 +08:00
										 |  |  | class Pose3 { | 
					
						
							|  |  |  | 	Pose3(); | 
					
						
							|  |  |  | 	Pose3(const Rot3& r, const Point3& t); | 
					
						
							|  |  |  | 	Pose3(Vector v); | 
					
						
							| 
									
										
										
										
											2011-12-02 02:57:32 +08:00
										 |  |  | 	Pose3(Matrix t); | 
					
						
							| 
									
										
										
										
											2011-12-07 11:05:37 +08:00
										 |  |  | 	static Pose3 Expmap(Vector v); | 
					
						
							| 
									
										
										
										
											2011-12-02 10:32:18 +08:00
										 |  |  | 	static Vector Logmap(const Pose3& p); | 
					
						
							| 
									
										
										
										
											2011-12-01 09:59:34 +08:00
										 |  |  | 	void print(string s) const; | 
					
						
							|  |  |  | 	bool equals(const Pose3& pose, double tol) const; | 
					
						
							|  |  |  | 	double x() const; | 
					
						
							|  |  |  | 	double y() const; | 
					
						
							|  |  |  | 	double z() const; | 
					
						
							| 
									
										
										
										
											2011-12-02 02:57:32 +08:00
										 |  |  | 	Matrix matrix() const; | 
					
						
							|  |  |  | 	Matrix adjointMap() const; | 
					
						
							| 
									
										
										
										
											2011-12-07 11:05:37 +08:00
										 |  |  | 	Pose3 compose(const Pose3& p2); | 
					
						
							|  |  |  | 	Pose3 between(const Pose3& p2); | 
					
						
							|  |  |  | 	Pose3 retract(Vector v); | 
					
						
							|  |  |  | 	Point3 translation() const; | 
					
						
							|  |  |  | 	Rot3 rotation() const; | 
					
						
							| 
									
										
										
										
											2011-12-01 09:59:34 +08:00
										 |  |  | }; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2011-10-21 13:07:35 +08:00
										 |  |  | class SharedGaussian { | 
					
						
							|  |  |  | 	SharedGaussian(Matrix covariance); | 
					
						
							| 
									
										
										
										
											2011-11-05 22:26:57 +08:00
										 |  |  | 	void print(string s) const; | 
					
						
							| 
									
										
										
										
											2011-10-21 13:07:35 +08:00
										 |  |  | }; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | class SharedDiagonal { | 
					
						
							|  |  |  | 	SharedDiagonal(Vector sigmas); | 
					
						
							| 
									
										
										
										
											2011-11-05 22:26:57 +08:00
										 |  |  | 	void print(string s) const; | 
					
						
							|  |  |  | 	Vector sample() const; | 
					
						
							| 
									
										
										
										
											2011-10-21 13:07:35 +08:00
										 |  |  | }; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2011-12-16 00:18:03 +08:00
										 |  |  | class SharedNoiseModel { | 
					
						
							| 
									
										
										
										
											2012-01-05 00:18:38 +08:00
										 |  |  | 	static SharedNoiseModel sharedSigmas(Vector sigmas); | 
					
						
							|  |  |  | 	static SharedNoiseModel sharedSigma(size_t dim, double sigma); | 
					
						
							|  |  |  | 	static SharedNoiseModel sharedPrecisions(Vector precisions); | 
					
						
							|  |  |  | 	static SharedNoiseModel sharedPrecision(size_t dim, double precision); | 
					
						
							|  |  |  | 	static SharedNoiseModel sharedUnit(size_t dim); | 
					
						
							|  |  |  | 	static SharedNoiseModel sharedSqrtInformation(Matrix R); | 
					
						
							|  |  |  | 	static SharedNoiseModel sharedCovariance(Matrix covariance); | 
					
						
							|  |  |  | 	void print(string s) const; | 
					
						
							| 
									
										
										
										
											2011-12-10 00:36:50 +08:00
										 |  |  | }; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2011-10-21 13:07:35 +08:00
										 |  |  | class VectorValues { | 
					
						
							|  |  |  | 	VectorValues(); | 
					
						
							| 
									
										
										
										
											2011-11-04 12:27:55 +08:00
										 |  |  | 	VectorValues(int nVars, int varDim); | 
					
						
							| 
									
										
										
										
											2011-10-21 13:07:35 +08:00
										 |  |  | 	void print(string s) const; | 
					
						
							|  |  |  | 	bool equals(const VectorValues& expected, double tol) const; | 
					
						
							| 
									
										
										
										
											2011-11-04 12:27:55 +08:00
										 |  |  | 	int size() const; | 
					
						
							| 
									
										
										
										
											2012-01-05 00:18:38 +08:00
										 |  |  | 	void insert(int j, Vector value); | 
					
						
							| 
									
										
										
										
											2011-10-21 13:07:35 +08:00
										 |  |  | }; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2011-10-23 03:42:02 +08:00
										 |  |  | class GaussianConditional { | 
					
						
							| 
									
										
										
										
											2011-11-04 12:27:55 +08:00
										 |  |  | 	GaussianConditional(int key, Vector d, Matrix R, Vector sigmas); | 
					
						
							|  |  |  | 	GaussianConditional(int key, Vector d, Matrix R, int name1, Matrix S, | 
					
						
							| 
									
										
										
										
											2011-10-23 03:42:02 +08:00
										 |  |  | 			Vector sigmas); | 
					
						
							| 
									
										
										
										
											2011-11-04 12:27:55 +08:00
										 |  |  | 	GaussianConditional(int key, Vector d, Matrix R, int name1, Matrix S, | 
					
						
							|  |  |  | 			int name2, Matrix T, Vector sigmas); | 
					
						
							| 
									
										
										
										
											2011-10-23 03:42:02 +08:00
										 |  |  | 	void print(string s) const; | 
					
						
							|  |  |  | 	bool equals(const GaussianConditional &cg, double tol) const; | 
					
						
							|  |  |  | }; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | class GaussianBayesNet { | 
					
						
							|  |  |  | 	GaussianBayesNet(); | 
					
						
							|  |  |  | 	void print(string s) const; | 
					
						
							|  |  |  | 	bool equals(const GaussianBayesNet& cbn, double tol) const; | 
					
						
							|  |  |  | 	void push_back(GaussianConditional* conditional); | 
					
						
							|  |  |  | 	void push_front(GaussianConditional* conditional); | 
					
						
							|  |  |  | }; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | class GaussianFactor { | 
					
						
							|  |  |  | 	void print(string s) const; | 
					
						
							|  |  |  | 	bool equals(const GaussianFactor& lf, double tol) const; | 
					
						
							|  |  |  | 	double error(const VectorValues& c) const; | 
					
						
							|  |  |  | }; | 
					
						
							| 
									
										
										
										
											2011-10-21 13:07:35 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2011-10-23 03:42:02 +08:00
										 |  |  | class JacobianFactor { | 
					
						
							|  |  |  | 	JacobianFactor(); | 
					
						
							|  |  |  | 	JacobianFactor(Vector b_in); | 
					
						
							| 
									
										
										
										
											2011-11-04 12:27:55 +08:00
										 |  |  | 	JacobianFactor(int i1, Matrix A1, Vector b, const SharedDiagonal& model); | 
					
						
							|  |  |  | 	JacobianFactor(int i1, Matrix A1, int i2, Matrix A2, Vector b, | 
					
						
							| 
									
										
										
										
											2011-10-23 03:42:02 +08:00
										 |  |  | 			const SharedDiagonal& model); | 
					
						
							| 
									
										
										
										
											2011-11-04 12:27:55 +08:00
										 |  |  | 	JacobianFactor(int i1, Matrix A1, int i2, Matrix A2, int i3, Matrix A3, | 
					
						
							|  |  |  | 			Vector b, const SharedDiagonal& model); | 
					
						
							| 
									
										
										
										
											2011-10-23 03:42:02 +08:00
										 |  |  | 	void print(string s) const; | 
					
						
							|  |  |  | 	bool equals(const GaussianFactor& lf, double tol) const; | 
					
						
							|  |  |  | 	bool empty() const; | 
					
						
							|  |  |  | 	Vector getb() const; | 
					
						
							|  |  |  | 	double error(const VectorValues& c) const; | 
					
						
							|  |  |  | 	GaussianConditional* eliminateFirst(); | 
					
						
							|  |  |  | }; | 
					
						
							| 
									
										
										
										
											2011-10-21 13:07:35 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2011-10-23 03:42:02 +08:00
										 |  |  | class GaussianFactorGraph { | 
					
						
							|  |  |  | 	GaussianFactorGraph(); | 
					
						
							|  |  |  | 	void print(string s) const; | 
					
						
							|  |  |  | 	bool equals(const GaussianFactorGraph& lfgraph, double tol) const; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2011-11-04 12:27:55 +08:00
										 |  |  | 	int size() const; | 
					
						
							| 
									
										
										
										
											2011-10-23 03:42:02 +08:00
										 |  |  | 	void push_back(GaussianFactor* ptr_f); | 
					
						
							|  |  |  | 	double error(const VectorValues& c) const; | 
					
						
							|  |  |  | 	double probPrime(const VectorValues& c) const; | 
					
						
							|  |  |  | 	void combine(const GaussianFactorGraph& lfg); | 
					
						
							| 
									
										
										
										
											2011-11-04 12:27:55 +08:00
										 |  |  | 	Matrix denseJacobian() const; | 
					
						
							|  |  |  | 	Matrix denseHessian() const; | 
					
						
							| 
									
										
										
										
											2011-10-31 04:38:08 +08:00
										 |  |  | 	Matrix sparseJacobian_() const; | 
					
						
							| 
									
										
										
										
											2011-10-23 03:42:02 +08:00
										 |  |  | }; | 
					
						
							| 
									
										
										
										
											2011-10-14 02:41:56 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2011-12-10 00:36:50 +08:00
										 |  |  | class GaussianSequentialSolver { | 
					
						
							|  |  |  |   GaussianSequentialSolver(const GaussianFactorGraph& graph, bool useQR); | 
					
						
							|  |  |  |   GaussianBayesNet* eliminate() const; | 
					
						
							|  |  |  |   VectorValues* optimize() const; | 
					
						
							|  |  |  |   GaussianFactor* marginalFactor(int j) const; | 
					
						
							|  |  |  |   Matrix marginalCovariance(int j) const; | 
					
						
							|  |  |  | }; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2011-11-04 08:27:02 +08:00
										 |  |  | class KalmanFilter { | 
					
						
							|  |  |  | 	KalmanFilter(Vector x, const SharedDiagonal& model); | 
					
						
							|  |  |  | 	void print(string s) const; | 
					
						
							|  |  |  | 	Vector mean() const; | 
					
						
							|  |  |  | 	Matrix information() const; | 
					
						
							|  |  |  | 	Matrix covariance() const; | 
					
						
							|  |  |  | 	void predict(Matrix F, Matrix B, Vector u, const SharedDiagonal& model); | 
					
						
							| 
									
										
										
										
											2011-11-04 22:10:32 +08:00
										 |  |  | 	void predict2(Matrix A0, Matrix A1, Vector b, const SharedDiagonal& model); | 
					
						
							| 
									
										
										
										
											2011-11-04 08:27:02 +08:00
										 |  |  | 	void update(Matrix H, Vector z, const SharedDiagonal& model); | 
					
						
							|  |  |  | }; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2011-11-04 12:27:55 +08:00
										 |  |  | class Ordering { | 
					
						
							|  |  |  | 	Ordering(); | 
					
						
							|  |  |  | 	void print(string s) const; | 
					
						
							|  |  |  | 	bool equals(const Ordering& ord, double tol) const; | 
					
						
							|  |  |  | 	void push_back(string key); | 
					
						
							| 
									
										
										
										
											2011-10-22 00:56:50 +08:00
										 |  |  | }; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2011-12-09 23:44:37 +08:00
										 |  |  | // Planar SLAM example domain
 | 
					
						
							| 
									
										
										
										
											2011-12-16 03:39:14 +08:00
										 |  |  | #include <gtsam/slam/planarSLAM.h>
 | 
					
						
							| 
									
										
										
										
											2011-12-09 23:44:37 +08:00
										 |  |  | namespace planarSLAM { | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2011-12-16 00:18:03 +08:00
										 |  |  | class Values { | 
					
						
							| 
									
										
										
										
											2011-12-09 23:44:37 +08:00
										 |  |  | 	Values(); | 
					
						
							| 
									
										
										
										
											2011-10-22 00:56:50 +08:00
										 |  |  | 	void print(string s) const; | 
					
						
							| 
									
										
										
										
											2011-12-09 23:44:37 +08:00
										 |  |  | 	Pose2 pose(int key) const; | 
					
						
							|  |  |  | 	Point2 point(int key) const; | 
					
						
							| 
									
										
										
										
											2011-10-22 00:56:50 +08:00
										 |  |  | 	void insertPose(int key, const Pose2& pose); | 
					
						
							|  |  |  | 	void insertPoint(int key, const Point2& point); | 
					
						
							|  |  |  | }; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2011-12-16 00:18:03 +08:00
										 |  |  | class Graph { | 
					
						
							| 
									
										
										
										
											2011-12-09 23:44:37 +08:00
										 |  |  | 	Graph(); | 
					
						
							| 
									
										
										
										
											2011-10-29 00:25:15 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | 	void print(string s) const; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2011-12-09 23:44:37 +08:00
										 |  |  | 	double error(const planarSLAM::Values& values) const; | 
					
						
							|  |  |  | 	Ordering* orderingCOLAMD(const planarSLAM::Values& values) const; | 
					
						
							|  |  |  | 	GaussianFactorGraph* linearize(const planarSLAM::Values& values, | 
					
						
							| 
									
										
										
										
											2011-11-04 12:27:55 +08:00
										 |  |  | 			const Ordering& ordering) const; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2011-11-06 05:17:32 +08:00
										 |  |  | 	void addPrior(int key, const Pose2& pose, const SharedNoiseModel& noiseModel); | 
					
						
							|  |  |  | 	void addPoseConstraint(int key, const Pose2& pose); | 
					
						
							|  |  |  | 	void addOdometry(int key1, int key2, const Pose2& odometry, const SharedNoiseModel& noiseModel); | 
					
						
							|  |  |  | 	void addBearing(int poseKey, int pointKey, const Rot2& bearing, const SharedNoiseModel& noiseModel); | 
					
						
							|  |  |  | 	void addRange(int poseKey, int pointKey, double range, const SharedNoiseModel& noiseModel); | 
					
						
							|  |  |  | 	void addBearingRange(int poseKey, int pointKey, const Rot2& bearing, double range, | 
					
						
							|  |  |  | 			const SharedNoiseModel& noiseModel); | 
					
						
							| 
									
										
										
										
											2011-12-09 23:44:37 +08:00
										 |  |  | 	planarSLAM::Values optimize(const planarSLAM::Values& initialEstimate); | 
					
						
							| 
									
										
										
										
											2011-10-22 00:56:50 +08:00
										 |  |  | }; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2011-12-16 00:18:03 +08:00
										 |  |  | class Odometry { | 
					
						
							| 
									
										
										
										
											2011-12-09 23:44:37 +08:00
										 |  |  | 	Odometry(int key1, int key2, const Pose2& measured, | 
					
						
							| 
									
										
										
										
											2011-11-04 12:27:55 +08:00
										 |  |  | 			const SharedNoiseModel& model); | 
					
						
							|  |  |  | 	void print(string s) const; | 
					
						
							| 
									
										
										
										
											2011-12-09 23:44:37 +08:00
										 |  |  | 	GaussianFactor* linearize(const planarSLAM::Values& center, const Ordering& ordering) const; | 
					
						
							| 
									
										
										
										
											2011-11-04 12:27:55 +08:00
										 |  |  | }; | 
					
						
							| 
									
										
										
										
											2011-11-29 05:31:34 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2011-12-09 23:44:37 +08:00
										 |  |  | }///\namespace planarSLAM
 | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2011-12-10 00:36:50 +08:00
										 |  |  | // Simulated2D Example Domain
 | 
					
						
							| 
									
										
										
										
											2011-12-16 03:39:14 +08:00
										 |  |  | #include <gtsam/slam/simulated2D.h>
 | 
					
						
							| 
									
										
										
										
											2011-12-10 00:36:50 +08:00
										 |  |  | namespace simulated2D { | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2011-12-16 00:18:03 +08:00
										 |  |  | class Values { | 
					
						
							| 
									
										
										
										
											2011-12-10 00:36:50 +08:00
										 |  |  | 	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); | 
					
						
							| 
									
										
										
										
											2011-11-29 05:31:34 +08:00
										 |  |  | }; | 
					
						
							| 
									
										
										
										
											2011-12-02 06:06:03 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2011-12-16 00:18:03 +08:00
										 |  |  | class Graph { | 
					
						
							| 
									
										
										
										
											2011-12-10 00:36:50 +08:00
										 |  |  | 	Graph(); | 
					
						
							|  |  |  | }; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | // TODO: add factors, etc.
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | }///\namespace simulated2D
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | // Simulated2DOriented Example Domain
 | 
					
						
							| 
									
										
										
										
											2011-12-16 03:39:14 +08:00
										 |  |  | #include <gtsam/slam/simulated2DOriented.h>
 | 
					
						
							| 
									
										
										
										
											2011-12-10 00:36:50 +08:00
										 |  |  | namespace simulated2DOriented { | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2011-12-16 00:18:03 +08:00
										 |  |  | class Values { | 
					
						
							| 
									
										
										
										
											2011-12-10 00:36:50 +08:00
										 |  |  | 	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); | 
					
						
							|  |  |  | }; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2011-12-16 00:18:03 +08:00
										 |  |  | class Graph { | 
					
						
							| 
									
										
										
										
											2011-12-10 00:36:50 +08:00
										 |  |  | 	Graph(); | 
					
						
							|  |  |  | }; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | // TODO: add factors, etc.
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | }///\namespace simulated2DOriented
 | 
					
						
							| 
									
										
										
										
											2011-12-07 11:05:35 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2011-12-02 06:06:03 +08:00
										 |  |  | //// 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
 | 
					
						
							|  |  |  | //
 | 
					
						
							|  |  |  | //class Ordering{
 | 
					
						
							|  |  |  | //	Ordering(string key);
 | 
					
						
							|  |  |  | //  void print(string s) const;
 | 
					
						
							|  |  |  | //  bool equals(const Ordering& ord, double tol) const;
 | 
					
						
							|  |  |  | //	Ordering subtract(const Ordering& keys) const;
 | 
					
						
							|  |  |  | //	void unique ();
 | 
					
						
							|  |  |  | //	void reverse ();
 | 
					
						
							|  |  |  | //  void push_back(string s);
 | 
					
						
							|  |  |  | //};
 | 
					
						
							|  |  |  | //
 | 
					
						
							|  |  |  | //class GaussianFactorSet {
 | 
					
						
							|  |  |  | //  GaussianFactorSet();
 | 
					
						
							|  |  |  | //  void push_back(GaussianFactor* factor);
 | 
					
						
							|  |  |  | //};
 | 
					
						
							|  |  |  | //
 | 
					
						
							|  |  |  | //class Simulated2DPosePrior {
 | 
					
						
							|  |  |  | //	Simulated2DPosePrior(Point2& mu, const SharedDiagonal& model, int i);
 | 
					
						
							|  |  |  | //  void print(string s) const;
 | 
					
						
							|  |  |  | //  double error(const Simulated2DValues& c) const;
 | 
					
						
							|  |  |  | //};
 | 
					
						
							|  |  |  | //
 | 
					
						
							|  |  |  | //class Simulated2DOrientedPosePrior {
 | 
					
						
							|  |  |  | //	Simulated2DOrientedPosePrior(Pose2& mu, const SharedDiagonal& model, int i);
 | 
					
						
							|  |  |  | //  void print(string s) const;
 | 
					
						
							|  |  |  | //  double error(const Simulated2DOrientedValues& c) const;
 | 
					
						
							|  |  |  | //};
 | 
					
						
							|  |  |  | //
 | 
					
						
							|  |  |  | //class Simulated2DPointPrior {
 | 
					
						
							|  |  |  | //	Simulated2DPointPrior(Point2& mu, const SharedDiagonal& model, int i);
 | 
					
						
							|  |  |  | //  void print(string s) const;
 | 
					
						
							|  |  |  | //  double error(const Simulated2DValues& c) const;
 | 
					
						
							|  |  |  | //};
 | 
					
						
							|  |  |  | //
 | 
					
						
							|  |  |  | //class Simulated2DOdometry {
 | 
					
						
							|  |  |  | //  Simulated2DOdometry(Point2& mu, const SharedDiagonal& model, int i1, int i2);
 | 
					
						
							|  |  |  | //  void print(string s) const;
 | 
					
						
							|  |  |  | //  double error(const Simulated2DValues& c) const;
 | 
					
						
							|  |  |  | //};
 | 
					
						
							|  |  |  | //
 | 
					
						
							|  |  |  | //class Simulated2DOrientedOdometry {
 | 
					
						
							|  |  |  | //	Simulated2DOrientedOdometry(Pose2& mu, const SharedDiagonal& model, int i1, int i2);
 | 
					
						
							|  |  |  | //  void print(string s) const;
 | 
					
						
							|  |  |  | //  double error(const Simulated2DOrientedValues& c) const;
 | 
					
						
							|  |  |  | //};
 | 
					
						
							|  |  |  | //
 | 
					
						
							|  |  |  | //class Simulated2DMeasurement {
 | 
					
						
							|  |  |  | //  Simulated2DMeasurement(Point2& mu, const SharedDiagonal& model, int i, int j);
 | 
					
						
							|  |  |  | //  void print(string s) const;
 | 
					
						
							|  |  |  | //  double error(const Simulated2DValues& c) const;
 | 
					
						
							|  |  |  | //};
 | 
					
						
							|  |  |  | //
 | 
					
						
							|  |  |  | //class GaussianFactor {
 | 
					
						
							|  |  |  | //	GaussianFactor(string key1,
 | 
					
						
							|  |  |  | //			Matrix A1,
 | 
					
						
							|  |  |  | //			Vector b_in,
 | 
					
						
							|  |  |  | //			const SharedDiagonal& model);
 | 
					
						
							|  |  |  | //	GaussianFactor(string key1,
 | 
					
						
							|  |  |  | //			Matrix A1,
 | 
					
						
							|  |  |  | //			string key2,
 | 
					
						
							|  |  |  | //			Matrix A2,
 | 
					
						
							|  |  |  | //			Vector b_in,
 | 
					
						
							|  |  |  | //			const SharedDiagonal& model);
 | 
					
						
							|  |  |  | //	GaussianFactor(string key1,
 | 
					
						
							|  |  |  | //			Matrix A1,
 | 
					
						
							|  |  |  | //			string key2,
 | 
					
						
							|  |  |  | //			Matrix A2,
 | 
					
						
							|  |  |  | //			string key3,
 | 
					
						
							|  |  |  | //			Matrix A3,
 | 
					
						
							|  |  |  | //			Vector b_in,
 | 
					
						
							|  |  |  | //			const SharedDiagonal& model);
 | 
					
						
							|  |  |  | //	bool involves(string key) const;
 | 
					
						
							|  |  |  | //	Matrix getA(string key) const;
 | 
					
						
							|  |  |  | //	pair<Matrix,Vector> matrix(const Ordering& ordering) const;
 | 
					
						
							|  |  |  | //	pair<GaussianConditional*,GaussianFactor*> eliminate(string key) const;
 | 
					
						
							|  |  |  | //};
 | 
					
						
							|  |  |  | //
 | 
					
						
							|  |  |  | //class GaussianFactorGraph {
 | 
					
						
							|  |  |  | //	GaussianConditional* eliminateOne(string key);
 | 
					
						
							|  |  |  | //	GaussianBayesNet* eliminate_(const Ordering& ordering);
 | 
					
						
							|  |  |  | //	VectorValues* optimize_(const Ordering& ordering);
 | 
					
						
							|  |  |  | //	pair<Matrix,Vector> matrix(const Ordering& ordering) const;
 | 
					
						
							|  |  |  | //	VectorValues* steepestDescent_(const VectorValues& x0) const;
 | 
					
						
							|  |  |  | //	VectorValues* conjugateGradientDescent_(const VectorValues& x0) const;
 | 
					
						
							|  |  |  | //};
 | 
					
						
							|  |  |  | //
 | 
					
						
							|  |  |  | //class Pose2Values{
 | 
					
						
							|  |  |  | //	Pose2Values();
 | 
					
						
							|  |  |  | //	Pose2 get(string key) const;
 | 
					
						
							|  |  |  | //	void insert(string name, const Pose2& val);
 | 
					
						
							|  |  |  | //	void print(string s) const;
 | 
					
						
							|  |  |  | //	void clear();
 | 
					
						
							|  |  |  | //	int size();
 | 
					
						
							|  |  |  | //};
 | 
					
						
							|  |  |  | //
 | 
					
						
							|  |  |  | //class Pose2Factor {
 | 
					
						
							|  |  |  | //	Pose2Factor(string key1, string key2,
 | 
					
						
							|  |  |  | //			const Pose2& measured, Matrix measurement_covariance);
 | 
					
						
							|  |  |  | //	void print(string name) const;
 | 
					
						
							|  |  |  | //	double error(const Pose2Values& c) const;
 | 
					
						
							|  |  |  | //	size_t size() const;
 | 
					
						
							|  |  |  | //	GaussianFactor* linearize(const Pose2Values& config) const;
 | 
					
						
							|  |  |  | //};
 | 
					
						
							|  |  |  | //
 | 
					
						
							|  |  |  | //class Pose2Graph{
 | 
					
						
							|  |  |  | //	Pose2Graph();
 | 
					
						
							|  |  |  | //	void print(string s) const;
 | 
					
						
							|  |  |  | //	GaussianFactorGraph* linearize_(const Pose2Values& config) const;
 | 
					
						
							|  |  |  | //	void push_back(Pose2Factor* factor);
 | 
					
						
							|  |  |  | //};
 | 
					
						
							|  |  |  | //
 | 
					
						
							|  |  |  | //class SymbolicFactor{
 | 
					
						
							|  |  |  | //	SymbolicFactor(const Ordering& keys);
 | 
					
						
							|  |  |  | //	void print(string s) const;
 | 
					
						
							|  |  |  | //};
 | 
					
						
							|  |  |  | //
 | 
					
						
							|  |  |  | //class Simulated2DPosePrior {
 | 
					
						
							|  |  |  | //	GaussianFactor* linearize(const Simulated2DValues& config) const;
 | 
					
						
							|  |  |  | //};
 | 
					
						
							|  |  |  | //
 | 
					
						
							|  |  |  | //class Simulated2DOrientedPosePrior {
 | 
					
						
							|  |  |  | //	GaussianFactor* linearize(const Simulated2DOrientedValues& config) const;
 | 
					
						
							|  |  |  | //};
 | 
					
						
							|  |  |  | //
 | 
					
						
							|  |  |  | //class Simulated2DPointPrior {
 | 
					
						
							|  |  |  | //	GaussianFactor* linearize(const Simulated2DValues& config) const;
 | 
					
						
							|  |  |  | //};
 | 
					
						
							|  |  |  | //
 | 
					
						
							|  |  |  | //class Simulated2DOdometry {
 | 
					
						
							|  |  |  | //	GaussianFactor* linearize(const Simulated2DValues& config) const;
 | 
					
						
							|  |  |  | //};
 | 
					
						
							|  |  |  | //
 | 
					
						
							|  |  |  | //class Simulated2DOrientedOdometry {
 | 
					
						
							|  |  |  | //	GaussianFactor* linearize(const Simulated2DOrientedValues& config) const;
 | 
					
						
							|  |  |  | //};
 | 
					
						
							|  |  |  | //
 | 
					
						
							|  |  |  | //class Simulated2DMeasurement {
 | 
					
						
							|  |  |  | //	GaussianFactor* linearize(const Simulated2DValues& config) const;
 | 
					
						
							|  |  |  | //};
 | 
					
						
							|  |  |  | //
 | 
					
						
							|  |  |  | //class Pose2SLAMOptimizer {
 | 
					
						
							|  |  |  | //	Pose2SLAMOptimizer(string dataset_name);
 | 
					
						
							|  |  |  | //	void print(string s) const;
 | 
					
						
							|  |  |  | //	void update(Vector x) const;
 | 
					
						
							|  |  |  | //	Vector optimize() const;
 | 
					
						
							|  |  |  | //	double error() const;
 | 
					
						
							|  |  |  | //	Matrix a1() const;
 | 
					
						
							|  |  |  | //	Matrix a2() const;
 | 
					
						
							|  |  |  | //	Vector b1() const;
 | 
					
						
							|  |  |  | //	Vector b2() const;
 | 
					
						
							|  |  |  | //};
 |