| 
									
										
										
										
											2012-05-04 01:03:16 +08:00
										 |  |  | /**
 | 
					
						
							| 
									
										
										
										
											2012-05-04 01:03:25 +08:00
										 |  |  |  * Matlab toolbox interface definition for gtsam_unstable | 
					
						
							| 
									
										
										
										
											2012-05-04 01:03:16 +08:00
										 |  |  |  */ | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | // specify the classes from gtsam we are using
 | 
					
						
							| 
									
										
										
										
											2012-07-14 05:55:05 +08:00
										 |  |  | virtual class gtsam::Value; | 
					
						
							|  |  |  | virtual class gtsam::Point3; | 
					
						
							|  |  |  | virtual class gtsam::Rot3; | 
					
						
							|  |  |  | virtual class gtsam::Pose3; | 
					
						
							|  |  |  | virtual class gtsam::noiseModel::Base; | 
					
						
							|  |  |  | virtual class gtsam::NonlinearFactor; | 
					
						
							| 
									
										
										
										
											2012-05-04 01:03:16 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2012-06-05 02:23:18 +08:00
										 |  |  | namespace gtsam { | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2012-06-15 09:01:25 +08:00
										 |  |  | #include <gtsam_unstable/base/Dummy.h>
 | 
					
						
							|  |  |  | class Dummy { | 
					
						
							|  |  |  |   Dummy(); | 
					
						
							|  |  |  |   void print(string s) const; | 
					
						
							| 
									
										
										
										
											2012-06-30 09:34:04 +08:00
										 |  |  |   unsigned char dummyTwoVar(unsigned char a) const; | 
					
						
							| 
									
										
										
										
											2012-06-15 09:01:25 +08:00
										 |  |  | }; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2012-05-04 01:03:25 +08:00
										 |  |  | #include <gtsam_unstable/dynamics/PoseRTV.h>
 | 
					
						
							| 
									
										
										
										
											2012-07-14 05:55:05 +08:00
										 |  |  | virtual class PoseRTV : gtsam::Value { | 
					
						
							| 
									
										
										
										
											2012-05-04 01:03:16 +08:00
										 |  |  | 	PoseRTV(); | 
					
						
							|  |  |  | 	PoseRTV(Vector rtv); | 
					
						
							|  |  |  | 	PoseRTV(const gtsam::Point3& pt, const gtsam::Rot3& rot, const gtsam::Point3& vel); | 
					
						
							|  |  |  | 	PoseRTV(const gtsam::Rot3& rot, const gtsam::Point3& pt, const gtsam::Point3& vel); | 
					
						
							|  |  |  | 	PoseRTV(const gtsam::Pose3& pose, const gtsam::Point3& vel); | 
					
						
							|  |  |  | 	PoseRTV(const gtsam::Pose3& pose); | 
					
						
							|  |  |  | 	PoseRTV(double roll, double pitch, double yaw, double x, double y, double z, double vx, double vy, double vz); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 	// testable
 | 
					
						
							| 
									
										
										
										
											2012-06-05 02:23:18 +08:00
										 |  |  | 	bool equals(const gtsam::PoseRTV& other, double tol) const; | 
					
						
							| 
									
										
										
										
											2012-05-04 01:03:16 +08:00
										 |  |  | 	void print(string s) const; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 	// access
 | 
					
						
							|  |  |  | 	gtsam::Point3 translation() const; | 
					
						
							|  |  |  | 	gtsam::Rot3 rotation() const; | 
					
						
							|  |  |  | 	gtsam::Point3 velocity() const; | 
					
						
							|  |  |  | 	gtsam::Pose3 pose() const; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 	// Vector interfaces
 | 
					
						
							|  |  |  | 	Vector vector() const; | 
					
						
							|  |  |  | 	Vector translationVec() const; | 
					
						
							|  |  |  | 	Vector velocityVec() const; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 	// manifold/Lie
 | 
					
						
							|  |  |  | 	static size_t Dim(); | 
					
						
							|  |  |  | 	size_t dim() const; | 
					
						
							| 
									
										
										
										
											2012-06-05 02:23:18 +08:00
										 |  |  | 	gtsam::PoseRTV retract(Vector v) const; | 
					
						
							|  |  |  | 	Vector localCoordinates(const gtsam::PoseRTV& p) const; | 
					
						
							|  |  |  | 	static gtsam::PoseRTV Expmap(Vector v); | 
					
						
							|  |  |  | 	static Vector Logmap(const gtsam::PoseRTV& p); | 
					
						
							|  |  |  | 	gtsam::PoseRTV inverse() const; | 
					
						
							|  |  |  | 	gtsam::PoseRTV compose(const gtsam::PoseRTV& p) const; | 
					
						
							|  |  |  | 	gtsam::PoseRTV between(const gtsam::PoseRTV& p) const; | 
					
						
							| 
									
										
										
										
											2012-05-04 01:03:16 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | 	// measurement
 | 
					
						
							| 
									
										
										
										
											2012-06-05 02:23:18 +08:00
										 |  |  | 	double range(const gtsam::PoseRTV& other) const; | 
					
						
							|  |  |  | 	gtsam::PoseRTV transformed_from(const gtsam::Pose3& trans) const; | 
					
						
							| 
									
										
										
										
											2012-05-04 01:03:16 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | 	// IMU/dynamics
 | 
					
						
							| 
									
										
										
										
											2012-06-05 02:23:18 +08:00
										 |  |  | 	gtsam::PoseRTV planarDynamics(double vel_rate, double heading_rate, double max_accel, double dt) const; | 
					
						
							|  |  |  | 	gtsam::PoseRTV flyingDynamics(double pitch_rate, double heading_rate, double lift_control, double dt) const; | 
					
						
							|  |  |  | 	gtsam::PoseRTV generalDynamics(Vector accel, Vector gyro, double dt) const; | 
					
						
							|  |  |  | 	Vector imuPrediction(const gtsam::PoseRTV& x2, double dt) const; | 
					
						
							|  |  |  | 	gtsam::Point3 translationIntegration(const gtsam::PoseRTV& x2, double dt) const; | 
					
						
							|  |  |  | 	Vector translationIntegrationVec(const gtsam::PoseRTV& x2, double dt) const; | 
					
						
							| 
									
										
										
										
											2012-05-04 01:03:16 +08:00
										 |  |  | }; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2012-07-14 05:55:05 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | // Nonlinear factors from gtsam, for our Value types
 | 
					
						
							|  |  |  | #include <gtsam/slam/PriorFactor.h>
 | 
					
						
							|  |  |  | template<T = {gtsam::PoseRTV}> | 
					
						
							|  |  |  | virtual class PriorFactor : gtsam::NonlinearFactor { | 
					
						
							|  |  |  | 	PriorFactor(size_t key, const T& prior, const gtsam::noiseModel::Base* noiseModel); | 
					
						
							|  |  |  | }; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | #include <gtsam/slam/BetweenFactor.h>
 | 
					
						
							|  |  |  | template<T = {gtsam::PoseRTV}> | 
					
						
							|  |  |  | virtual class BetweenFactor : gtsam::NonlinearFactor { | 
					
						
							|  |  |  | 	BetweenFactor(size_t key1, size_t key2, const T& relativePose, const gtsam::noiseModel::Base* noiseModel); | 
					
						
							|  |  |  | }; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | #include <gtsam/slam/RangeFactor.h>
 | 
					
						
							|  |  |  | template<POSE, POINT> | 
					
						
							|  |  |  | virtual class RangeFactor : gtsam::NonlinearFactor { | 
					
						
							|  |  |  | 	RangeFactor(size_t key1, size_t key2, double measured, const gtsam::noiseModel::Base* noiseModel); | 
					
						
							|  |  |  | }; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | typedef gtsam::RangeFactor<gtsam::PoseRTV, gtsam::PoseRTV> RangeFactorRTV; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | #include <gtsam/nonlinear/NonlinearEquality.h>
 | 
					
						
							|  |  |  | template<T = {gtsam::PoseRTV}> | 
					
						
							|  |  |  | virtual class NonlinearEquality : gtsam::NonlinearFactor { | 
					
						
							|  |  |  | 	// Constructor - forces exact evaluation
 | 
					
						
							|  |  |  | 	NonlinearEquality(size_t j, const T& feasible); | 
					
						
							|  |  |  | 	// Constructor - allows inexact evaluation
 | 
					
						
							|  |  |  | 	NonlinearEquality(size_t j, const T& feasible, double error_gain); | 
					
						
							|  |  |  | }; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2012-07-23 02:49:07 +08:00
										 |  |  | #include <gtsam_unstable/dynamics/IMUFactor.h>
 | 
					
						
							| 
									
										
										
										
											2012-07-14 05:55:05 +08:00
										 |  |  | template<POSE = {gtsam::PoseRTV}> | 
					
						
							|  |  |  | virtual class IMUFactor : gtsam::NonlinearFactor { | 
					
						
							|  |  |  | 	/** Standard constructor */ | 
					
						
							|  |  |  | 	IMUFactor(Vector accel, Vector gyro, | 
					
						
							|  |  |  | 		double dt, size_t key1, size_t key2, const gtsam::noiseModel::Base* model); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 	/** Full IMU vector specification */ | 
					
						
							|  |  |  | 	IMUFactor(Vector imu_vector, | 
					
						
							|  |  |  | 		double dt, size_t key1, size_t key2, const gtsam::noiseModel::Base* model); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 	Vector gyro() const; | 
					
						
							|  |  |  | 	Vector accel() const; | 
					
						
							|  |  |  | 	Vector z() const; | 
					
						
							|  |  |  | 	size_t key1() const; | 
					
						
							|  |  |  | 	size_t key2() const; | 
					
						
							|  |  |  | }; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2012-07-23 02:49:07 +08:00
										 |  |  | #include <gtsam_unstable/dynamics/FullIMUFactor.h>
 | 
					
						
							| 
									
										
										
										
											2012-07-14 05:55:05 +08:00
										 |  |  | template<POSE = {gtsam::PoseRTV}> | 
					
						
							|  |  |  | virtual class FullIMUFactor : gtsam::NonlinearFactor { | 
					
						
							|  |  |  | 	/** Standard constructor */ | 
					
						
							|  |  |  | 	FullIMUFactor(Vector accel, Vector gyro, | 
					
						
							|  |  |  | 		double dt, size_t key1, size_t key2, const gtsam::noiseModel::Base* model); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 	/** Single IMU vector - imu = [accel, gyro] */ | 
					
						
							|  |  |  | 	FullIMUFactor(Vector imu, | 
					
						
							|  |  |  | 		double dt, size_t key1, size_t key2, const gtsam::noiseModel::Base* model); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 	Vector gyro() const; | 
					
						
							|  |  |  | 	Vector accel() const; | 
					
						
							|  |  |  | 	Vector z() const; | 
					
						
							|  |  |  | 	size_t key1() const; | 
					
						
							|  |  |  | 	size_t key2() const; | 
					
						
							|  |  |  | }; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2012-07-18 02:30:02 +08:00
										 |  |  | #include <gtsam_unstable/dynamics/DynamicsPriors.h>
 | 
					
						
							| 
									
										
										
										
											2012-07-14 05:55:05 +08:00
										 |  |  | virtual class DHeightPrior : gtsam::NonlinearFactor { | 
					
						
							|  |  |  | 	DHeightPrior(size_t key, double height, const gtsam::noiseModel::Base* model); | 
					
						
							|  |  |  | }; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | virtual class DRollPrior : gtsam::NonlinearFactor { | 
					
						
							|  |  |  | 	/** allows for explicit roll parameterization - uses canonical coordinate */ | 
					
						
							|  |  |  | 	DRollPrior(size_t key, double wx, const gtsam::noiseModel::Base* model); | 
					
						
							|  |  |  | 	/** Forces roll to zero */ | 
					
						
							|  |  |  | 	DRollPrior(size_t key, const gtsam::noiseModel::Base* model); | 
					
						
							|  |  |  | }; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | virtual class VelocityPrior : gtsam::NonlinearFactor { | 
					
						
							|  |  |  | 	VelocityPrior(size_t key, Vector vel, const gtsam::noiseModel::Base* model); | 
					
						
							|  |  |  | }; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | virtual class DGroundConstraint : gtsam::NonlinearFactor { | 
					
						
							|  |  |  | 	// Primary constructor allows for variable height of the "floor"
 | 
					
						
							|  |  |  |   DGroundConstraint(size_t key, double height, const gtsam::noiseModel::Base* model); | 
					
						
							|  |  |  | 	// Fully specify vector - use only for debugging
 | 
					
						
							|  |  |  |   DGroundConstraint(size_t key, Vector constraint, const gtsam::noiseModel::Base* model); | 
					
						
							|  |  |  | }; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2012-06-05 02:23:18 +08:00
										 |  |  | }///\namespace gtsam
 |