| 
									
										
										
										
											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; | 
					
						
							| 
									
										
										
										
											2014-11-08 05:41:21 +08:00
										 |  |  | class gtsam::Vector6; | 
					
						
							|  |  |  | class gtsam::Point2; | 
					
						
							| 
									
										
										
										
											2015-05-04 08:31:08 +08:00
										 |  |  | class gtsam::Point2Vector; | 
					
						
							| 
									
										
										
										
											2014-11-08 05:41:21 +08:00
										 |  |  | class gtsam::Rot2; | 
					
						
							|  |  |  | class gtsam::Pose2; | 
					
						
							|  |  |  | class gtsam::Point3; | 
					
						
							| 
									
										
											  
											
												Feature/shonan averaging (#473)
Shonan Rotation Averaging.
199 commit messages below, many are obsolete as design has changed quite a bit over time, especially from the earlier period where I thought we only needed SO(4).
* prototyping weighted sampler
* Moved WeightedSampler into its own header
* Random now uses std header <random>.
* Removed boost/random usage from linear and discrete directories
* Made into class
* Now using new WeightedSampler class
* Inlined random direction generation
* eradicated last vestiges of boost/random in gtsam_unstable
* Added 3D example g2o file
* Added Frobenius norm factors
* Shonan averaging algorithm, using SOn class
* Wrapping Frobenius and Shonan
* Fixed issues with <<
* Use Builder parameters
* Refactored Shonan interface
* Fixed << issues as well as MATLAB segfault, using eval(), as discussed in issue #451
* ShonanAveragingParameters
* New factor FrobeniusWormholeFactorP computes |Rj*P - Ri*P*Rij|
* Fixed broken GetDimension for Lie groups with variable dimension.
* Removed all but Shonan averaging factor and made everything work with new SOn
* Just a single WormholeFactor, wrapped noise model
* Use std <random>
* comments/todos
* added timing script
* add script to process ShonanAveraging timing results
* Now producing a CSV file
* Parse csv file and make combined plot
* Fixed range
* change p value and set two flags on
* input file path, all the csv files proceeses at the same time
* add check convergence rate part
* csv file have name according to input  data name
* correct one mistake in initialization
* generate the convergence rate for each p value
* add yticks for the bar plot
* add noises to the measurements
* test add noise
* Basic structure for checkOptimalityAt
* change optimizer method to cholesky
* buildQ now working. Tests should be better but visually inspected.
* multiple test with cholesky
* back
* computeLambda now works
* make combined plots while make bar plot
* Calculate minimum eigenvalue - the very expensive version
* Exposed computeMinEigenValue
* make plots and bar  togenter
* method change to jacobi
* add time for check optimality, min_eigen_value, sub_bound
* updated plot min_eigen value and subounds
* Adding Spectra headers
* David's min eigenvalue code inserted and made to compile.
* Made it work
* Made "run" method work.
* add rim.g2o name
* Fixed bug in shifting eigenvalues
* roundSolution which replaces projectFrom
* removed extra arguments
* Added to wrapper
* Add SOn to template lists
* roundSolution delete the extra arguement p
* only calculate p=5 and change to the correct way computing f_R
* Fixed conflict and made Google-style name changes
* prototype descent code and unit test for initializeWithDescent
* add averaging cost/time part in processing data
* initializewithDescent success in test
* Formatting and find example rather than hardcode
* Removed accidentally checked in cmake files
* give value to xi by block
* correct gradient descent
* correct xi
* }
* Fix wrapper
* Make Hat/Vee have alternating signs
* MakeATangentVector helpder function
* Fixed cmake files
* changed sign
* add line search
* unit test for line search
* test real data with line search
* correct comment
* Fix boost::uniform_real
* add save .dat file
* correct test case
* add explanation
* delete redundant cout
* add name to .dat output file
* correct checkR
* add get poses_  in shonan
* add Vector Point type for savig data
* Remove cmake file which magically re-appeared??
* Switched to std random library.
* Prepare Klaus test
* Add klaus3.g2o data.
* fix comment
* Fix derivatives
* Fixed broken GetDimension for Lie groups with variable dimension.
* Fix SOn tests to report correct dimension
* Added tests for Klaus3 data
* Add runWithRandomKlaus test for shonan.
* Finish runWithRandomKlaus unittest.
* Correct datafile.
* Correct the format.
* Added measured and keys methods
* Shonan works on Klaus data
* Create dense versions for wrappers, for testing
* Now store D, Q, and L
* Remove another cmake file incorrectly checked in.
* Found and fixed the bug in ComputeLambda !
* Now using Q in Lambdas calculation, so Lambdas agree with Eriksson18cvpr.
* Make FrobeniusFactor not use deprecated methods
* FrobeniusWormholeFactor takes Rot3 as argument
* Wrapped some more methods.
* Wrapped more methods
* Allow creating and populating BetweenFactorPose3s in python
* New constructors for ShonanAveraging
* add function of get measurements number
* Remove option not to use noise model
* wrap Use nrMeasurements
* Made Logmap a bit more tolerant of slightly degenerate rotations (with trace < -1)
* Allow for Anchor index
* Fix anchor bug
* Change outside view to Rot3 rather than SO3
* Add Lift in SOn class
* Make comet working
* Small fixes
* Delete extra function
* Add SOn::Lift
* Removed hardcoded flag
* Moved Frobenius factor to gtsam from unstable
* Added new tests and made an old regression pass again
* Cleaned up formatting and some comments, added EXPORT directives
* Throw exception if wrongly dimensioned values are given
* static_cast and other throw
* Fixed run-time dimension
* Added gauge-constraining factor
* LM parameters now passed in, added Gauge fixing
* 2D test scaffold
* Comments
* Pre-allocated generators
* Document API
* Add optional weight
* New prior weeights infrastructure
* Made d a template parameter
* Recursive Hat and RetractJacobian test
* Added Spectra 0.9.0 to 3rdparty
* Enabling 2D averaging
* Templatized Wormhole factor
* ignore xcode folder
* Fixed vec and VectorizedGenerators templates for fixed N!=3 or 4
* Simplifying constructors
Moved file loading to tests (for now)
All unit tests pass for d==3!
* Templated some methods internally
* Very generic parseToVector
* refactored load2d
* Very much improved FrobeniusWormholeFactor (Shonan) Jacobians
* SO(2) averaging works !
* Templated parse methods
* Switched to new Dataset paradigm
* Moved Shonan to gtsam
* Checked noise model is correctly gotten from file
* Fixed covariance bug
* Making Shonan wrapper work
* Renamed FrobeniusWormholeFactor to ShonanFactor and moved into its own compilation unit in gtsam/sfm
* Fixed wrong include
* Simplified interface (removed irrelevant random inits) and fixed eigenvector test
* Removed stray boost::none
* Added citation as suggested by Jose
* Made descent test deterministic
* Fixed some comments, commented out flaky test
Co-authored-by: Jing Wu <jingwu@gatech.edu>
Co-authored-by: jingwuOUO <wujing2951@gmail.com>
Co-authored-by: swang <swang736@gatech.edu>
Co-authored-by: ss <ss>
Co-authored-by: Fan Jiang <prof.fan@foxmail.com>
											
										 
											2020-08-17 19:43:10 +08:00
										 |  |  | class gtsam::SO3; | 
					
						
							|  |  |  | class gtsam::SO4; | 
					
						
							|  |  |  | class gtsam::SOn; | 
					
						
							| 
									
										
										
										
											2014-11-08 05:41:21 +08:00
										 |  |  | class gtsam::Rot3; | 
					
						
							|  |  |  | class gtsam::Pose3; | 
					
						
							| 
									
										
										
										
											2012-07-14 05:55:05 +08:00
										 |  |  | virtual class gtsam::noiseModel::Base; | 
					
						
							| 
									
										
										
										
											2013-08-07 23:25:00 +08:00
										 |  |  | virtual class gtsam::noiseModel::Gaussian; | 
					
						
							| 
									
										
											  
											
												Feature/shonan averaging (#473)
Shonan Rotation Averaging.
199 commit messages below, many are obsolete as design has changed quite a bit over time, especially from the earlier period where I thought we only needed SO(4).
* prototyping weighted sampler
* Moved WeightedSampler into its own header
* Random now uses std header <random>.
* Removed boost/random usage from linear and discrete directories
* Made into class
* Now using new WeightedSampler class
* Inlined random direction generation
* eradicated last vestiges of boost/random in gtsam_unstable
* Added 3D example g2o file
* Added Frobenius norm factors
* Shonan averaging algorithm, using SOn class
* Wrapping Frobenius and Shonan
* Fixed issues with <<
* Use Builder parameters
* Refactored Shonan interface
* Fixed << issues as well as MATLAB segfault, using eval(), as discussed in issue #451
* ShonanAveragingParameters
* New factor FrobeniusWormholeFactorP computes |Rj*P - Ri*P*Rij|
* Fixed broken GetDimension for Lie groups with variable dimension.
* Removed all but Shonan averaging factor and made everything work with new SOn
* Just a single WormholeFactor, wrapped noise model
* Use std <random>
* comments/todos
* added timing script
* add script to process ShonanAveraging timing results
* Now producing a CSV file
* Parse csv file and make combined plot
* Fixed range
* change p value and set two flags on
* input file path, all the csv files proceeses at the same time
* add check convergence rate part
* csv file have name according to input  data name
* correct one mistake in initialization
* generate the convergence rate for each p value
* add yticks for the bar plot
* add noises to the measurements
* test add noise
* Basic structure for checkOptimalityAt
* change optimizer method to cholesky
* buildQ now working. Tests should be better but visually inspected.
* multiple test with cholesky
* back
* computeLambda now works
* make combined plots while make bar plot
* Calculate minimum eigenvalue - the very expensive version
* Exposed computeMinEigenValue
* make plots and bar  togenter
* method change to jacobi
* add time for check optimality, min_eigen_value, sub_bound
* updated plot min_eigen value and subounds
* Adding Spectra headers
* David's min eigenvalue code inserted and made to compile.
* Made it work
* Made "run" method work.
* add rim.g2o name
* Fixed bug in shifting eigenvalues
* roundSolution which replaces projectFrom
* removed extra arguments
* Added to wrapper
* Add SOn to template lists
* roundSolution delete the extra arguement p
* only calculate p=5 and change to the correct way computing f_R
* Fixed conflict and made Google-style name changes
* prototype descent code and unit test for initializeWithDescent
* add averaging cost/time part in processing data
* initializewithDescent success in test
* Formatting and find example rather than hardcode
* Removed accidentally checked in cmake files
* give value to xi by block
* correct gradient descent
* correct xi
* }
* Fix wrapper
* Make Hat/Vee have alternating signs
* MakeATangentVector helpder function
* Fixed cmake files
* changed sign
* add line search
* unit test for line search
* test real data with line search
* correct comment
* Fix boost::uniform_real
* add save .dat file
* correct test case
* add explanation
* delete redundant cout
* add name to .dat output file
* correct checkR
* add get poses_  in shonan
* add Vector Point type for savig data
* Remove cmake file which magically re-appeared??
* Switched to std random library.
* Prepare Klaus test
* Add klaus3.g2o data.
* fix comment
* Fix derivatives
* Fixed broken GetDimension for Lie groups with variable dimension.
* Fix SOn tests to report correct dimension
* Added tests for Klaus3 data
* Add runWithRandomKlaus test for shonan.
* Finish runWithRandomKlaus unittest.
* Correct datafile.
* Correct the format.
* Added measured and keys methods
* Shonan works on Klaus data
* Create dense versions for wrappers, for testing
* Now store D, Q, and L
* Remove another cmake file incorrectly checked in.
* Found and fixed the bug in ComputeLambda !
* Now using Q in Lambdas calculation, so Lambdas agree with Eriksson18cvpr.
* Make FrobeniusFactor not use deprecated methods
* FrobeniusWormholeFactor takes Rot3 as argument
* Wrapped some more methods.
* Wrapped more methods
* Allow creating and populating BetweenFactorPose3s in python
* New constructors for ShonanAveraging
* add function of get measurements number
* Remove option not to use noise model
* wrap Use nrMeasurements
* Made Logmap a bit more tolerant of slightly degenerate rotations (with trace < -1)
* Allow for Anchor index
* Fix anchor bug
* Change outside view to Rot3 rather than SO3
* Add Lift in SOn class
* Make comet working
* Small fixes
* Delete extra function
* Add SOn::Lift
* Removed hardcoded flag
* Moved Frobenius factor to gtsam from unstable
* Added new tests and made an old regression pass again
* Cleaned up formatting and some comments, added EXPORT directives
* Throw exception if wrongly dimensioned values are given
* static_cast and other throw
* Fixed run-time dimension
* Added gauge-constraining factor
* LM parameters now passed in, added Gauge fixing
* 2D test scaffold
* Comments
* Pre-allocated generators
* Document API
* Add optional weight
* New prior weeights infrastructure
* Made d a template parameter
* Recursive Hat and RetractJacobian test
* Added Spectra 0.9.0 to 3rdparty
* Enabling 2D averaging
* Templatized Wormhole factor
* ignore xcode folder
* Fixed vec and VectorizedGenerators templates for fixed N!=3 or 4
* Simplifying constructors
Moved file loading to tests (for now)
All unit tests pass for d==3!
* Templated some methods internally
* Very generic parseToVector
* refactored load2d
* Very much improved FrobeniusWormholeFactor (Shonan) Jacobians
* SO(2) averaging works !
* Templated parse methods
* Switched to new Dataset paradigm
* Moved Shonan to gtsam
* Checked noise model is correctly gotten from file
* Fixed covariance bug
* Making Shonan wrapper work
* Renamed FrobeniusWormholeFactor to ShonanFactor and moved into its own compilation unit in gtsam/sfm
* Fixed wrong include
* Simplified interface (removed irrelevant random inits) and fixed eigenvector test
* Removed stray boost::none
* Added citation as suggested by Jose
* Made descent test deterministic
* Fixed some comments, commented out flaky test
Co-authored-by: Jing Wu <jingwu@gatech.edu>
Co-authored-by: jingwuOUO <wujing2951@gmail.com>
Co-authored-by: swang <swang736@gatech.edu>
Co-authored-by: ss <ss>
Co-authored-by: Fan Jiang <prof.fan@foxmail.com>
											
										 
											2020-08-17 19:43:10 +08:00
										 |  |  | virtual class gtsam::noiseModel::Isotropic; | 
					
						
							| 
									
										
										
										
											2013-08-03 00:04:17 +08:00
										 |  |  | virtual class gtsam::imuBias::ConstantBias; | 
					
						
							| 
									
										
										
										
											2012-07-14 05:55:05 +08:00
										 |  |  | virtual class gtsam::NonlinearFactor; | 
					
						
							| 
									
										
										
										
											2014-05-05 22:14:56 +08:00
										 |  |  | virtual class gtsam::NoiseModelFactor; | 
					
						
							| 
									
										
										
										
											2022-12-24 22:35:45 +08:00
										 |  |  | virtual class gtsam::NoiseModelFactorN; | 
					
						
							| 
									
										
										
										
											2012-09-21 22:19:57 +08:00
										 |  |  | virtual class gtsam::GaussianFactor; | 
					
						
							|  |  |  | virtual class gtsam::HessianFactor; | 
					
						
							|  |  |  | virtual class gtsam::JacobianFactor; | 
					
						
							| 
									
										
										
										
											2014-11-08 05:41:21 +08:00
										 |  |  | class gtsam::Cal3_S2; | 
					
						
							|  |  |  | class gtsam::Cal3DS2; | 
					
						
							| 
									
										
										
										
											2012-09-21 22:19:57 +08:00
										 |  |  | class gtsam::GaussianFactorGraph; | 
					
						
							|  |  |  | class gtsam::NonlinearFactorGraph; | 
					
						
							|  |  |  | class gtsam::Ordering; | 
					
						
							|  |  |  | class gtsam::Values; | 
					
						
							| 
									
										
										
										
											2013-04-16 03:54:46 +08:00
										 |  |  | class gtsam::Key; | 
					
						
							|  |  |  | class gtsam::VectorValues; | 
					
						
							|  |  |  | class gtsam::KeyList; | 
					
						
							| 
									
										
										
										
											2013-03-24 04:19:43 +08:00
										 |  |  | class gtsam::KeySet; | 
					
						
							|  |  |  | class gtsam::KeyVector; | 
					
						
							| 
									
										
										
										
											2013-04-16 03:54:46 +08:00
										 |  |  | class gtsam::LevenbergMarquardtParams; | 
					
						
							|  |  |  | class gtsam::ISAM2Params; | 
					
						
							| 
									
										
										
										
											2013-05-21 07:28:38 +08:00
										 |  |  | class gtsam::GaussianDensity; | 
					
						
							| 
									
										
											  
											
												Feature/shonan averaging (#473)
Shonan Rotation Averaging.
199 commit messages below, many are obsolete as design has changed quite a bit over time, especially from the earlier period where I thought we only needed SO(4).
* prototyping weighted sampler
* Moved WeightedSampler into its own header
* Random now uses std header <random>.
* Removed boost/random usage from linear and discrete directories
* Made into class
* Now using new WeightedSampler class
* Inlined random direction generation
* eradicated last vestiges of boost/random in gtsam_unstable
* Added 3D example g2o file
* Added Frobenius norm factors
* Shonan averaging algorithm, using SOn class
* Wrapping Frobenius and Shonan
* Fixed issues with <<
* Use Builder parameters
* Refactored Shonan interface
* Fixed << issues as well as MATLAB segfault, using eval(), as discussed in issue #451
* ShonanAveragingParameters
* New factor FrobeniusWormholeFactorP computes |Rj*P - Ri*P*Rij|
* Fixed broken GetDimension for Lie groups with variable dimension.
* Removed all but Shonan averaging factor and made everything work with new SOn
* Just a single WormholeFactor, wrapped noise model
* Use std <random>
* comments/todos
* added timing script
* add script to process ShonanAveraging timing results
* Now producing a CSV file
* Parse csv file and make combined plot
* Fixed range
* change p value and set two flags on
* input file path, all the csv files proceeses at the same time
* add check convergence rate part
* csv file have name according to input  data name
* correct one mistake in initialization
* generate the convergence rate for each p value
* add yticks for the bar plot
* add noises to the measurements
* test add noise
* Basic structure for checkOptimalityAt
* change optimizer method to cholesky
* buildQ now working. Tests should be better but visually inspected.
* multiple test with cholesky
* back
* computeLambda now works
* make combined plots while make bar plot
* Calculate minimum eigenvalue - the very expensive version
* Exposed computeMinEigenValue
* make plots and bar  togenter
* method change to jacobi
* add time for check optimality, min_eigen_value, sub_bound
* updated plot min_eigen value and subounds
* Adding Spectra headers
* David's min eigenvalue code inserted and made to compile.
* Made it work
* Made "run" method work.
* add rim.g2o name
* Fixed bug in shifting eigenvalues
* roundSolution which replaces projectFrom
* removed extra arguments
* Added to wrapper
* Add SOn to template lists
* roundSolution delete the extra arguement p
* only calculate p=5 and change to the correct way computing f_R
* Fixed conflict and made Google-style name changes
* prototype descent code and unit test for initializeWithDescent
* add averaging cost/time part in processing data
* initializewithDescent success in test
* Formatting and find example rather than hardcode
* Removed accidentally checked in cmake files
* give value to xi by block
* correct gradient descent
* correct xi
* }
* Fix wrapper
* Make Hat/Vee have alternating signs
* MakeATangentVector helpder function
* Fixed cmake files
* changed sign
* add line search
* unit test for line search
* test real data with line search
* correct comment
* Fix boost::uniform_real
* add save .dat file
* correct test case
* add explanation
* delete redundant cout
* add name to .dat output file
* correct checkR
* add get poses_  in shonan
* add Vector Point type for savig data
* Remove cmake file which magically re-appeared??
* Switched to std random library.
* Prepare Klaus test
* Add klaus3.g2o data.
* fix comment
* Fix derivatives
* Fixed broken GetDimension for Lie groups with variable dimension.
* Fix SOn tests to report correct dimension
* Added tests for Klaus3 data
* Add runWithRandomKlaus test for shonan.
* Finish runWithRandomKlaus unittest.
* Correct datafile.
* Correct the format.
* Added measured and keys methods
* Shonan works on Klaus data
* Create dense versions for wrappers, for testing
* Now store D, Q, and L
* Remove another cmake file incorrectly checked in.
* Found and fixed the bug in ComputeLambda !
* Now using Q in Lambdas calculation, so Lambdas agree with Eriksson18cvpr.
* Make FrobeniusFactor not use deprecated methods
* FrobeniusWormholeFactor takes Rot3 as argument
* Wrapped some more methods.
* Wrapped more methods
* Allow creating and populating BetweenFactorPose3s in python
* New constructors for ShonanAveraging
* add function of get measurements number
* Remove option not to use noise model
* wrap Use nrMeasurements
* Made Logmap a bit more tolerant of slightly degenerate rotations (with trace < -1)
* Allow for Anchor index
* Fix anchor bug
* Change outside view to Rot3 rather than SO3
* Add Lift in SOn class
* Make comet working
* Small fixes
* Delete extra function
* Add SOn::Lift
* Removed hardcoded flag
* Moved Frobenius factor to gtsam from unstable
* Added new tests and made an old regression pass again
* Cleaned up formatting and some comments, added EXPORT directives
* Throw exception if wrongly dimensioned values are given
* static_cast and other throw
* Fixed run-time dimension
* Added gauge-constraining factor
* LM parameters now passed in, added Gauge fixing
* 2D test scaffold
* Comments
* Pre-allocated generators
* Document API
* Add optional weight
* New prior weeights infrastructure
* Made d a template parameter
* Recursive Hat and RetractJacobian test
* Added Spectra 0.9.0 to 3rdparty
* Enabling 2D averaging
* Templatized Wormhole factor
* ignore xcode folder
* Fixed vec and VectorizedGenerators templates for fixed N!=3 or 4
* Simplifying constructors
Moved file loading to tests (for now)
All unit tests pass for d==3!
* Templated some methods internally
* Very generic parseToVector
* refactored load2d
* Very much improved FrobeniusWormholeFactor (Shonan) Jacobians
* SO(2) averaging works !
* Templated parse methods
* Switched to new Dataset paradigm
* Moved Shonan to gtsam
* Checked noise model is correctly gotten from file
* Fixed covariance bug
* Making Shonan wrapper work
* Renamed FrobeniusWormholeFactor to ShonanFactor and moved into its own compilation unit in gtsam/sfm
* Fixed wrong include
* Simplified interface (removed irrelevant random inits) and fixed eigenvector test
* Removed stray boost::none
* Added citation as suggested by Jose
* Made descent test deterministic
* Fixed some comments, commented out flaky test
Co-authored-by: Jing Wu <jingwu@gatech.edu>
Co-authored-by: jingwuOUO <wujing2951@gmail.com>
Co-authored-by: swang <swang736@gatech.edu>
Co-authored-by: ss <ss>
Co-authored-by: Fan Jiang <prof.fan@foxmail.com>
											
										 
											2020-08-17 19:43:10 +08:00
										 |  |  | class gtsam::LevenbergMarquardtOptimizer; | 
					
						
							| 
									
										
										
										
											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> | 
					
						
							| 
									
										
										
										
											2014-11-08 05:41:21 +08:00
										 |  |  | class PoseRTV {
 | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  |   PoseRTV(); | 
					
						
							|  |  |  |   PoseRTV(Vector rtv); | 
					
						
							| 
									
										
										
										
											2015-07-18 08:36:29 +08:00
										 |  |  |   PoseRTV(const gtsam::Point3& pt, const gtsam::Rot3& rot, const Vector& vel); | 
					
						
							|  |  |  |   PoseRTV(const gtsam::Rot3& rot, const gtsam::Point3& pt, const Vector& vel); | 
					
						
							|  |  |  |   PoseRTV(const gtsam::Pose3& pose, const Vector& vel); | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  |   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 | 
					
						
							|  |  |  |   bool equals(const gtsam::PoseRTV& other, double tol) const; | 
					
						
							|  |  |  |   void print(string s) const; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   // access | 
					
						
							|  |  |  |   gtsam::Point3 translation() const; | 
					
						
							|  |  |  |   gtsam::Rot3 rotation() const; | 
					
						
							| 
									
										
										
										
											2015-07-18 08:36:29 +08:00
										 |  |  |   Vector velocity() const; | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  |   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; | 
					
						
							|  |  |  |   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; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   // measurement | 
					
						
							|  |  |  |   double range(const gtsam::PoseRTV& other) const; | 
					
						
							|  |  |  |   gtsam::PoseRTV transformed_from(const gtsam::Pose3& trans) const; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   // IMU/dynamics | 
					
						
							|  |  |  |   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; | 
					
						
							| 
									
										
										
										
											2013-06-20 01:50:07 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   void serializable() const; // enabling serialization functionality | 
					
						
							| 
									
										
										
										
											2012-05-04 01:03:16 +08:00
										 |  |  | }; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-03-24 04:19:30 +08:00
										 |  |  | #include <gtsam_unstable/geometry/Pose3Upright.h> | 
					
						
							| 
									
										
										
										
											2014-11-08 05:41:21 +08:00
										 |  |  | class Pose3Upright {
 | 
					
						
							| 
									
										
										
										
											2013-03-24 04:19:30 +08:00
										 |  |  |   Pose3Upright(); | 
					
						
							| 
									
										
										
										
											2017-08-15 23:16:13 +08:00
										 |  |  |   Pose3Upright(const gtsam::Pose3Upright& other); | 
					
						
							| 
									
										
										
										
											2013-03-24 04:19:30 +08:00
										 |  |  |   Pose3Upright(const gtsam::Rot2& bearing, const gtsam::Point3& t); | 
					
						
							|  |  |  |   Pose3Upright(double x, double y, double z, double theta); | 
					
						
							|  |  |  |   Pose3Upright(const gtsam::Pose2& pose, double z); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   void print(string s) const; | 
					
						
							|  |  |  |   bool equals(const gtsam::Pose3Upright& pose, double tol) const; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   double x() const; | 
					
						
							|  |  |  |   double y() const; | 
					
						
							|  |  |  |   double z() const; | 
					
						
							|  |  |  |   double theta() const; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   gtsam::Point2 translation2() const; | 
					
						
							|  |  |  |   gtsam::Point3 translation() const; | 
					
						
							|  |  |  |   gtsam::Rot2 rotation2() const; | 
					
						
							|  |  |  |   gtsam::Rot3 rotation() const; | 
					
						
							|  |  |  |   gtsam::Pose2 pose2() const; | 
					
						
							|  |  |  |   gtsam::Pose3 pose() const; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   size_t dim() const; | 
					
						
							|  |  |  |   gtsam::Pose3Upright retract(Vector v) const; | 
					
						
							|  |  |  |   Vector localCoordinates(const gtsam::Pose3Upright& p2) const; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2022-07-08 00:31:27 +08:00
										 |  |  |   static gtsam::Pose3Upright Identity(); | 
					
						
							| 
									
										
										
										
											2013-03-24 04:19:30 +08:00
										 |  |  |   gtsam::Pose3Upright inverse() const; | 
					
						
							|  |  |  |   gtsam::Pose3Upright compose(const gtsam::Pose3Upright& p2) const; | 
					
						
							|  |  |  |   gtsam::Pose3Upright between(const gtsam::Pose3Upright& p2) const; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   static gtsam::Pose3Upright Expmap(Vector xi); | 
					
						
							|  |  |  |   static Vector Logmap(const gtsam::Pose3Upright& p); | 
					
						
							| 
									
										
										
										
											2013-06-20 01:50:07 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   void serializable() const; // enabling serialization functionality | 
					
						
							| 
									
										
										
										
											2013-03-24 04:19:30 +08:00
										 |  |  | }; // \class Pose3Upright | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | #include <gtsam_unstable/geometry/BearingS2.h> | 
					
						
							| 
									
										
										
										
											2014-11-08 05:41:21 +08:00
										 |  |  | class BearingS2 {
 | 
					
						
							| 
									
										
										
										
											2013-03-24 04:19:30 +08:00
										 |  |  |   BearingS2(); | 
					
						
							| 
									
										
										
										
											2017-08-15 23:16:13 +08:00
										 |  |  |   BearingS2(double azimuth_double, double elevation_double); | 
					
						
							| 
									
										
										
										
											2013-03-24 04:19:30 +08:00
										 |  |  |   BearingS2(const gtsam::Rot2& azimuth, const gtsam::Rot2& elevation); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   gtsam::Rot2 azimuth() const; | 
					
						
							|  |  |  |   gtsam::Rot2 elevation() const; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   static gtsam::BearingS2 fromDownwardsObservation(const gtsam::Pose3& A, const gtsam::Point3& B); | 
					
						
							|  |  |  |   static gtsam::BearingS2 fromForwardObservation(const gtsam::Pose3& A, const gtsam::Point3& B); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   void print(string s) const; | 
					
						
							|  |  |  |   bool equals(const gtsam::BearingS2& x, double tol) const; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   size_t dim() const; | 
					
						
							|  |  |  |   gtsam::BearingS2 retract(Vector v) const; | 
					
						
							|  |  |  |   Vector localCoordinates(const gtsam::BearingS2& p2) const; | 
					
						
							| 
									
										
										
										
											2013-06-20 01:50:07 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   void serializable() const; // enabling serialization functionality | 
					
						
							| 
									
										
										
										
											2013-03-24 04:19:30 +08:00
										 |  |  | }; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2021-02-20 05:08:43 +08:00
										 |  |  |    | 
					
						
							| 
									
										
										
										
											2013-03-24 04:19:40 +08:00
										 |  |  | #include <gtsam_unstable/geometry/SimWall2D.h> | 
					
						
							| 
									
										
										
										
											2013-03-24 04:19:32 +08:00
										 |  |  | class SimWall2D {
 | 
					
						
							|  |  |  |   SimWall2D(); | 
					
						
							|  |  |  |   SimWall2D(const gtsam::Point2& a, const gtsam::Point2& b); | 
					
						
							|  |  |  |   SimWall2D(double ax, double ay, double bx, double by); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   void print(string s) const; | 
					
						
							|  |  |  |   bool equals(const gtsam::SimWall2D& other, double tol) const; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   gtsam::Point2 a() const; | 
					
						
							|  |  |  |   gtsam::Point2 b() const; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   gtsam::SimWall2D scale(double s) const; | 
					
						
							|  |  |  |   double length() const; | 
					
						
							|  |  |  |   gtsam::Point2 midpoint() const; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   bool intersects(const gtsam::SimWall2D& wall) const; | 
					
						
							| 
									
										
										
										
											2023-01-14 06:12:15 +08:00
										 |  |  |   //   bool intersects(const gtsam::SimWall2D& wall, gtsam::Point2* pt = nullptr) const; | 
					
						
							| 
									
										
										
										
											2013-03-24 04:19:32 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   gtsam::Point2 norm() const; | 
					
						
							|  |  |  |   gtsam::Rot2 reflection(const gtsam::Point2& init, const gtsam::Point2& intersection) const; | 
					
						
							|  |  |  | }; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-03-24 04:19:40 +08:00
										 |  |  | #include <gtsam_unstable/geometry/SimPolygon2D.h> | 
					
						
							|  |  |  | class SimPolygon2D {
 | 
					
						
							| 
									
										
										
										
											2013-03-24 04:19:32 +08:00
										 |  |  |    static void seedGenerator(size_t seed); | 
					
						
							|  |  |  |    static gtsam::SimPolygon2D createTriangle(const gtsam::Point2& pA, const gtsam::Point2& pB, const gtsam::Point2& pC); | 
					
						
							|  |  |  |    static gtsam::SimPolygon2D createRectangle(const gtsam::Point2& p, double height, double width); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |    static gtsam::SimPolygon2D randomTriangle(double side_len, double mean_side_len, double sigma_side_len, | 
					
						
							|  |  |  |        double min_vertex_dist, double min_side_len, const gtsam::SimPolygon2DVector& existing_polys); | 
					
						
							|  |  |  |    static gtsam::SimPolygon2D randomRectangle(double side_len, double mean_side_len, double sigma_side_len, | 
					
						
							|  |  |  |        double min_vertex_dist, double min_side_len, const gtsam::SimPolygon2DVector& existing_polys); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |    gtsam::Point2 landmark(size_t i) const; | 
					
						
							|  |  |  |    size_t size() const; | 
					
						
							|  |  |  |    gtsam::Point2Vector vertices() const; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |    bool equals(const gtsam::SimPolygon2D& p, double tol) const; | 
					
						
							|  |  |  |    void print(string s) const; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |    gtsam::SimWall2DVector walls() const; | 
					
						
							|  |  |  |    bool contains(const gtsam::Point2& p) const; | 
					
						
							|  |  |  |    bool overlaps(const gtsam::SimPolygon2D& p) const; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |    static bool anyContains(const gtsam::Point2& p, const gtsam::SimPolygon2DVector& obstacles); | 
					
						
							|  |  |  |    static bool anyOverlaps(const gtsam::SimPolygon2D& p, const gtsam::SimPolygon2DVector& obstacles); | 
					
						
							|  |  |  |    static bool insideBox(double s, const gtsam::Point2& p); | 
					
						
							|  |  |  |    static bool nearExisting(const gtsam::Point2Vector& S, | 
					
						
							|  |  |  |        const gtsam::Point2& p, double threshold); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |    static gtsam::Point2 randomPoint2(double s); | 
					
						
							|  |  |  |    static gtsam::Rot2 randomAngle(); | 
					
						
							|  |  |  |    static double randomDistance(double mu, double sigma); | 
					
						
							|  |  |  |    static double randomDistance(double mu, double sigma, double min_dist); | 
					
						
							|  |  |  |    static gtsam::Point2 randomBoundedPoint2(double boundary_size, | 
					
						
							|  |  |  |        const gtsam::Point2Vector& landmarks, double min_landmark_dist); | 
					
						
							|  |  |  |    static gtsam::Point2 randomBoundedPoint2(double boundary_size, | 
					
						
							|  |  |  |        const gtsam::Point2Vector& landmarks, | 
					
						
							|  |  |  |        const gtsam::SimPolygon2DVector& obstacles, double min_landmark_dist); | 
					
						
							|  |  |  |    static gtsam::Point2 randomBoundedPoint2(double boundary_size, | 
					
						
							|  |  |  |        const gtsam::SimPolygon2DVector& obstacles); | 
					
						
							|  |  |  |    static gtsam::Point2 randomBoundedPoint2( | 
					
						
							|  |  |  |        const gtsam::Point2& LL_corner, const gtsam::Point2& UR_corner, | 
					
						
							|  |  |  |        const gtsam::Point2Vector& landmarks, | 
					
						
							|  |  |  |        const gtsam::SimPolygon2DVector& obstacles, double min_landmark_dist); | 
					
						
							|  |  |  |    static gtsam::Pose2 randomFreePose(double boundary_size, const gtsam::SimPolygon2DVector& obstacles); | 
					
						
							|  |  |  |  }; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |  // std::vector<gtsam::SimWall2D> | 
					
						
							|  |  |  |  class SimWall2DVector | 
					
						
							|  |  |  |  {
 | 
					
						
							|  |  |  |    //Capacity | 
					
						
							|  |  |  |    size_t size() const; | 
					
						
							|  |  |  |    size_t max_size() const; | 
					
						
							|  |  |  |    void resize(size_t sz); | 
					
						
							|  |  |  |    size_t capacity() const; | 
					
						
							|  |  |  |    bool empty() const; | 
					
						
							|  |  |  |    void reserve(size_t n); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |    //Element access | 
					
						
							|  |  |  |    gtsam::SimWall2D at(size_t n) const; | 
					
						
							|  |  |  |    gtsam::SimWall2D front() const; | 
					
						
							|  |  |  |    gtsam::SimWall2D back() const; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |    //Modifiers | 
					
						
							|  |  |  |    void assign(size_t n, const gtsam::SimWall2D& u); | 
					
						
							|  |  |  |    void push_back(const gtsam::SimWall2D& x); | 
					
						
							|  |  |  |    void pop_back(); | 
					
						
							|  |  |  |  }; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |  // std::vector<gtsam::SimPolygon2D> | 
					
						
							|  |  |  |  class SimPolygon2DVector | 
					
						
							|  |  |  |  {
 | 
					
						
							|  |  |  |    //Capacity | 
					
						
							|  |  |  |    size_t size() const; | 
					
						
							|  |  |  |    size_t max_size() const; | 
					
						
							|  |  |  |    void resize(size_t sz); | 
					
						
							|  |  |  |    size_t capacity() const; | 
					
						
							|  |  |  |    bool empty() const; | 
					
						
							|  |  |  |    void reserve(size_t n); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |    //Element access | 
					
						
							|  |  |  |    gtsam::SimPolygon2D at(size_t n) const; | 
					
						
							|  |  |  |    gtsam::SimPolygon2D front() const; | 
					
						
							|  |  |  |    gtsam::SimPolygon2D back() const; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |    //Modifiers | 
					
						
							|  |  |  |    void assign(size_t n, const gtsam::SimPolygon2D& u); | 
					
						
							|  |  |  |    void push_back(const gtsam::SimPolygon2D& x); | 
					
						
							|  |  |  |    void pop_back(); | 
					
						
							|  |  |  |  }; | 
					
						
							| 
									
										
										
										
											2012-07-14 05:55:05 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | // Nonlinear factors from gtsam, for our Value types | 
					
						
							| 
									
										
										
										
											2020-04-11 10:26:22 +08:00
										 |  |  | #include <gtsam/nonlinear/PriorFactor.h> | 
					
						
							| 
									
										
										
										
											2012-07-14 05:55:05 +08:00
										 |  |  | template<T = {gtsam::PoseRTV}> | 
					
						
							| 
									
										
										
										
											2017-03-19 03:52:08 +08:00
										 |  |  | virtual class PriorFactor : gtsam::NoiseModelFactor {
 | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  |   PriorFactor(size_t key, const T& prior, const gtsam::noiseModel::Base* noiseModel); | 
					
						
							| 
									
										
										
										
											2013-06-20 01:50:07 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   void serializable() const; // enabling serialization functionality | 
					
						
							| 
									
										
										
										
											2012-07-14 05:55:05 +08:00
										 |  |  | }; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | #include <gtsam/slam/BetweenFactor.h> | 
					
						
							|  |  |  | template<T = {gtsam::PoseRTV}> | 
					
						
							| 
									
										
										
										
											2017-03-19 03:52:08 +08:00
										 |  |  | virtual class BetweenFactor : gtsam::NoiseModelFactor {
 | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  |   BetweenFactor(size_t key1, size_t key2, const T& relativePose, const gtsam::noiseModel::Base* noiseModel); | 
					
						
							| 
									
										
										
										
											2013-06-20 01:50:07 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   void serializable() const; // enabling serialization functionality | 
					
						
							| 
									
										
										
										
											2012-07-14 05:55:05 +08:00
										 |  |  | }; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-08-08 23:12:21 +08:00
										 |  |  | #include <gtsam_unstable/slam/BetweenFactorEM.h> | 
					
						
							|  |  |  | template<T = {gtsam::Pose2}> | 
					
						
							|  |  |  | virtual class BetweenFactorEM : gtsam::NonlinearFactor {
 | 
					
						
							|  |  |  |   BetweenFactorEM(size_t key1, size_t key2, const T& relativePose, | 
					
						
							|  |  |  |       const gtsam::noiseModel::Gaussian* model_inlier, const gtsam::noiseModel::Gaussian* model_outlier, | 
					
						
							|  |  |  |       double prior_inlier, double prior_outlier); | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-08-30 06:43:09 +08:00
										 |  |  |   BetweenFactorEM(size_t key1, size_t key2, const T& relativePose, | 
					
						
							|  |  |  |         const gtsam::noiseModel::Gaussian* model_inlier, const gtsam::noiseModel::Gaussian* model_outlier, | 
					
						
							|  |  |  |         double prior_inlier, double prior_outlier,  bool flag_bump_up_near_zero_probs); | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-08-08 23:12:21 +08:00
										 |  |  |   Vector whitenedError(const gtsam::Values& x); | 
					
						
							| 
									
										
										
										
											2013-08-09 04:13:39 +08:00
										 |  |  |   Vector unwhitenedError(const gtsam::Values& x); | 
					
						
							| 
									
										
										
										
											2013-08-08 23:12:21 +08:00
										 |  |  |   Vector calcIndicatorProb(const gtsam::Values& x); | 
					
						
							| 
									
										
										
										
											2013-08-23 23:24:46 +08:00
										 |  |  |   gtsam::Pose2 measured(); // TODO: figure out how to output a template instead | 
					
						
							|  |  |  |   void set_flag_bump_up_near_zero_probs(bool flag); | 
					
						
							|  |  |  |   bool get_flag_bump_up_near_zero_probs() const; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2014-07-01 01:43:25 +08:00
										 |  |  |   void updateNoiseModels(const gtsam::Values& values, const gtsam::NonlinearFactorGraph& graph); | 
					
						
							| 
									
										
										
										
											2014-07-31 21:22:54 +08:00
										 |  |  |   void updateNoiseModels_givenCovs(const gtsam::Values& values, Matrix cov1, Matrix cov2, Matrix cov12); | 
					
						
							| 
									
										
										
										
											2014-07-01 01:43:25 +08:00
										 |  |  |   Matrix get_model_inlier_cov(); | 
					
						
							|  |  |  |   Matrix get_model_outlier_cov(); | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-08-23 23:24:46 +08:00
										 |  |  |   void serializable() const; // enabling serialization functionality | 
					
						
							|  |  |  | }; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | #include <gtsam_unstable/slam/TransformBtwRobotsUnaryFactorEM.h> | 
					
						
							|  |  |  | template<T = {gtsam::Pose2}> | 
					
						
							|  |  |  | virtual class TransformBtwRobotsUnaryFactorEM : gtsam::NonlinearFactor {
 | 
					
						
							|  |  |  |   TransformBtwRobotsUnaryFactorEM(size_t key, const T& relativePose, size_t keyA, size_t keyB, | 
					
						
							|  |  |  |       const gtsam::Values& valA, const gtsam::Values& valB, | 
					
						
							|  |  |  |       const gtsam::noiseModel::Gaussian* model_inlier, const gtsam::noiseModel::Gaussian* model_outlier, | 
					
						
							|  |  |  |       double prior_inlier, double prior_outlier); | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-08-29 00:56:57 +08:00
										 |  |  |   TransformBtwRobotsUnaryFactorEM(size_t key, const T& relativePose, size_t keyA, size_t keyB, | 
					
						
							|  |  |  |         const gtsam::Values& valA, const gtsam::Values& valB, | 
					
						
							|  |  |  |         const gtsam::noiseModel::Gaussian* model_inlier, const gtsam::noiseModel::Gaussian* model_outlier, | 
					
						
							| 
									
										
										
										
											2013-08-30 06:43:09 +08:00
										 |  |  |         double prior_inlier, double prior_outlier, bool flag_bump_up_near_zero_probs, bool start_with_M_step); | 
					
						
							| 
									
										
										
										
											2013-08-29 00:56:57 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-08-23 23:24:46 +08:00
										 |  |  |   Vector whitenedError(const gtsam::Values& x); | 
					
						
							|  |  |  |   Vector unwhitenedError(const gtsam::Values& x); | 
					
						
							|  |  |  |   Vector calcIndicatorProb(const gtsam::Values& x); | 
					
						
							|  |  |  |   void setValAValB(const gtsam::Values valA, const gtsam::Values valB); | 
					
						
							| 
									
										
										
										
											2013-08-08 23:12:21 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2014-09-10 05:22:59 +08:00
										 |  |  |   void updateNoiseModels(const gtsam::Values& values, const gtsam::NonlinearFactorGraph& graph); | 
					
						
							|  |  |  |   void updateNoiseModels_givenCovs(const gtsam::Values& values, Matrix cov1, Matrix cov2, Matrix cov12); | 
					
						
							|  |  |  |   Matrix get_model_inlier_cov(); | 
					
						
							|  |  |  |   Matrix get_model_outlier_cov(); | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-08-08 23:12:21 +08:00
										 |  |  |   void serializable() const; // enabling serialization functionality | 
					
						
							|  |  |  | }; | 
					
						
							| 
									
										
										
										
											2012-07-14 05:55:05 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2014-02-05 03:13:25 +08:00
										 |  |  | #include <gtsam_unstable/slam/TransformBtwRobotsUnaryFactor.h> | 
					
						
							|  |  |  | template<T = {gtsam::Pose2}> | 
					
						
							|  |  |  | virtual class TransformBtwRobotsUnaryFactor : gtsam::NonlinearFactor {
 | 
					
						
							|  |  |  |   TransformBtwRobotsUnaryFactor(size_t key, const T& relativePose, size_t keyA, size_t keyB, | 
					
						
							|  |  |  |       const gtsam::Values& valA, const gtsam::Values& valB, | 
					
						
							|  |  |  |       const gtsam::noiseModel::Gaussian* model); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   Vector whitenedError(const gtsam::Values& x); | 
					
						
							|  |  |  |   Vector unwhitenedError(const gtsam::Values& x); | 
					
						
							|  |  |  |   void setValAValB(const gtsam::Values valA, const gtsam::Values valB); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   void serializable() const; // enabling serialization functionality | 
					
						
							|  |  |  | }; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-09-14 05:00:48 +08:00
										 |  |  | #include <gtsam_unstable/slam/SmartRangeFactor.h> | 
					
						
							|  |  |  | virtual class SmartRangeFactor : gtsam::NoiseModelFactor {
 | 
					
						
							|  |  |  |   SmartRangeFactor(double s); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   void addRange(size_t key, double measuredRange); | 
					
						
							|  |  |  |   gtsam::Point2 triangulate(const gtsam::Values& x) const; | 
					
						
							| 
									
										
										
										
											2017-03-19 03:52:08 +08:00
										 |  |  |   //void print(string s) const; | 
					
						
							| 
									
										
										
										
											2013-09-14 05:00:48 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | }; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2015-07-13 03:06:55 +08:00
										 |  |  | #include <gtsam/sam/RangeFactor.h> | 
					
						
							| 
									
										
										
										
											2012-07-14 05:55:05 +08:00
										 |  |  | template<POSE, POINT> | 
					
						
							| 
									
										
										
										
											2017-03-19 03:52:08 +08:00
										 |  |  | virtual class RangeFactor : gtsam::NoiseModelFactor {
 | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  |   RangeFactor(size_t key1, size_t key2, double measured, const gtsam::noiseModel::Base* noiseModel); | 
					
						
							| 
									
										
										
										
											2013-06-20 01:50:07 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   void serializable() const; // enabling serialization functionality | 
					
						
							| 
									
										
										
										
											2012-07-14 05:55:05 +08:00
										 |  |  | }; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | typedef gtsam::RangeFactor<gtsam::PoseRTV, gtsam::PoseRTV> RangeFactorRTV; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2020-03-19 05:28:40 +08:00
										 |  |  | #include <gtsam_unstable/geometry/Event.h> | 
					
						
							|  |  |  | class Event {
 | 
					
						
							|  |  |  |   Event(); | 
					
						
							|  |  |  |   Event(double t, const gtsam::Point3& p); | 
					
						
							|  |  |  |   Event(double t, double x, double y, double z); | 
					
						
							|  |  |  |   double time() const; | 
					
						
							|  |  |  |   gtsam::Point3 location() const; | 
					
						
							|  |  |  |   double height() const; | 
					
						
							|  |  |  |   void print(string s) const; | 
					
						
							|  |  |  | }; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | class TimeOfArrival {
 | 
					
						
							|  |  |  |   TimeOfArrival(); | 
					
						
							|  |  |  |   TimeOfArrival(double speed); | 
					
						
							|  |  |  |   double measure(const gtsam::Event& event, const gtsam::Point3& sensor) const; | 
					
						
							|  |  |  | }; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | #include <gtsam_unstable/slam/TOAFactor.h> | 
					
						
							|  |  |  | virtual class TOAFactor : gtsam::NonlinearFactor {
 | 
					
						
							|  |  |  |   // For now, because of overload issues, we only expose constructor with known sensor coordinates: | 
					
						
							|  |  |  |   TOAFactor(size_t key1, gtsam::Point3 sensor, double measured, | 
					
						
							|  |  |  |             const gtsam::noiseModel::Base* noiseModel); | 
					
						
							|  |  |  |   static void InsertEvent(size_t key, const gtsam::Event& event, gtsam::Values* values); | 
					
						
							|  |  |  | }; | 
					
						
							| 
									
										
										
										
											2012-07-14 05:55:05 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | #include <gtsam/nonlinear/NonlinearEquality.h> | 
					
						
							|  |  |  | template<T = {gtsam::PoseRTV}> | 
					
						
							| 
									
										
										
										
											2017-03-19 03:52:08 +08:00
										 |  |  | virtual class NonlinearEquality : gtsam::NoiseModelFactor {
 | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  |   // 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); | 
					
						
							| 
									
										
										
										
											2013-06-20 01:50:07 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   void serializable() const; // enabling serialization functionality | 
					
						
							| 
									
										
										
										
											2012-07-14 05:55:05 +08:00
										 |  |  | }; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											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}> | 
					
						
							| 
									
										
										
										
											2017-03-19 03:52:08 +08:00
										 |  |  | virtual class IMUFactor : gtsam::NoiseModelFactor {
 | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  |   /** Standard constructor */ | 
					
						
							|  |  |  |   IMUFactor(Vector accel, Vector gyro, | 
					
						
							|  |  |  |     double dt, size_t key1, size_t key2, const gtsam::noiseModel::Base* model); | 
					
						
							| 
									
										
										
										
											2012-07-14 05:55:05 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  |   /** Full IMU vector specification */ | 
					
						
							|  |  |  |   IMUFactor(Vector imu_vector, | 
					
						
							|  |  |  |     double dt, size_t key1, size_t key2, const gtsam::noiseModel::Base* model); | 
					
						
							| 
									
										
										
										
											2012-07-14 05:55:05 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  |   Vector gyro() const; | 
					
						
							|  |  |  |   Vector accel() const; | 
					
						
							|  |  |  |   Vector z() const; | 
					
						
							| 
									
										
										
										
											2022-12-24 22:35:45 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   template <I = {1, 2}> | 
					
						
							|  |  |  |   size_t key() const; | 
					
						
							| 
									
										
										
										
											2012-07-14 05:55:05 +08:00
										 |  |  | }; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											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}> | 
					
						
							| 
									
										
										
										
											2017-03-19 03:52:08 +08:00
										 |  |  | virtual class FullIMUFactor : gtsam::NoiseModelFactor {
 | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  |   /** Standard constructor */ | 
					
						
							|  |  |  |   FullIMUFactor(Vector accel, Vector gyro, | 
					
						
							|  |  |  |     double dt, size_t key1, size_t key2, const gtsam::noiseModel::Base* model); | 
					
						
							| 
									
										
										
										
											2012-07-14 05:55:05 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  |   /** Single IMU vector - imu = [accel, gyro] */ | 
					
						
							|  |  |  |   FullIMUFactor(Vector imu, | 
					
						
							|  |  |  |     double dt, size_t key1, size_t key2, const gtsam::noiseModel::Base* model); | 
					
						
							| 
									
										
										
										
											2012-07-14 05:55:05 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  |   Vector gyro() const; | 
					
						
							|  |  |  |   Vector accel() const; | 
					
						
							|  |  |  |   Vector z() const; | 
					
						
							| 
									
										
										
										
											2022-12-24 22:35:45 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   template <I = {1, 2}> | 
					
						
							|  |  |  |   size_t key() const; | 
					
						
							| 
									
										
										
										
											2012-07-14 05:55:05 +08:00
										 |  |  | }; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											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 {
 | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  |   DHeightPrior(size_t key, double height, const gtsam::noiseModel::Base* model); | 
					
						
							| 
									
										
										
										
											2012-07-14 05:55:05 +08:00
										 |  |  | }; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | virtual class DRollPrior : gtsam::NonlinearFactor {
 | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  |   /** 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); | 
					
						
							| 
									
										
										
										
											2012-07-14 05:55:05 +08:00
										 |  |  | }; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | virtual class VelocityPrior : gtsam::NonlinearFactor {
 | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  |   VelocityPrior(size_t key, Vector vel, const gtsam::noiseModel::Base* model); | 
					
						
							| 
									
										
										
										
											2012-07-14 05:55:05 +08:00
										 |  |  | }; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | virtual class DGroundConstraint : gtsam::NonlinearFactor {
 | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  |   // Primary constructor allows for variable height of the "floor" | 
					
						
							| 
									
										
										
										
											2012-07-14 05:55:05 +08:00
										 |  |  |   DGroundConstraint(size_t key, double height, const gtsam::noiseModel::Base* model); | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  |   // Fully specify vector - use only for debugging | 
					
						
							| 
									
										
										
										
											2012-07-14 05:55:05 +08:00
										 |  |  |   DGroundConstraint(size_t key, Vector constraint, const gtsam::noiseModel::Base* model); | 
					
						
							|  |  |  | }; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-04-11 20:07:42 +08:00
										 |  |  | #include <gtsam_unstable/dynamics/VelocityConstraint3.h> | 
					
						
							|  |  |  | virtual class VelocityConstraint3 : gtsam::NonlinearFactor {
 | 
					
						
							|  |  |  |   /** Standard constructor */ | 
					
						
							|  |  |  |   VelocityConstraint3(size_t key1, size_t key2, size_t velKey, double dt); | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2020-09-27 06:01:26 +08:00
										 |  |  |   Vector evaluateError(const double& x1, const double& x2, const double& v) const; | 
					
						
							| 
									
										
										
										
											2013-04-11 20:07:42 +08:00
										 |  |  | }; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-04-16 05:31:47 +08:00
										 |  |  | #include <gtsam_unstable/dynamics/Pendulum.h> | 
					
						
							|  |  |  | virtual class PendulumFactor1 : gtsam::NonlinearFactor {
 | 
					
						
							|  |  |  |   /** Standard constructor */ | 
					
						
							|  |  |  |   PendulumFactor1(size_t k1, size_t k, size_t velKey, double dt); | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2020-09-27 06:01:26 +08:00
										 |  |  |   Vector evaluateError(const double& qk1, const double& qk, const double& v) const; | 
					
						
							| 
									
										
										
										
											2013-04-16 05:31:47 +08:00
										 |  |  | }; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2017-03-19 03:52:08 +08:00
										 |  |  | #include <gtsam_unstable/dynamics/Pendulum.h> | 
					
						
							| 
									
										
										
										
											2013-04-16 05:31:47 +08:00
										 |  |  | virtual class PendulumFactor2 : gtsam::NonlinearFactor {
 | 
					
						
							|  |  |  |   /** Standard constructor */ | 
					
						
							|  |  |  |   PendulumFactor2(size_t vk1, size_t vk, size_t qKey, double dt, double L, double g); | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2020-09-27 06:01:26 +08:00
										 |  |  |   Vector evaluateError(const double& vk1, const double& vk, const double& q) const; | 
					
						
							| 
									
										
										
										
											2013-04-16 05:31:47 +08:00
										 |  |  | }; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-04-17 03:07:59 +08:00
										 |  |  | virtual class PendulumFactorPk : gtsam::NonlinearFactor {
 | 
					
						
							|  |  |  |   /** Standard constructor */ | 
					
						
							|  |  |  |   PendulumFactorPk(size_t pk, size_t qk, size_t qk1, double h, double m, double r, double g, double alpha); | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2020-09-27 06:01:26 +08:00
										 |  |  |   Vector evaluateError(const double& pk, const double& qk, const double& qk1) const; | 
					
						
							| 
									
										
										
										
											2013-04-17 03:07:59 +08:00
										 |  |  | }; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | virtual class PendulumFactorPk1 : gtsam::NonlinearFactor {
 | 
					
						
							|  |  |  |   /** Standard constructor */ | 
					
						
							|  |  |  |   PendulumFactorPk1(size_t pk1, size_t qk, size_t qk1, double h, double m, double r, double g, double alpha); | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2020-09-27 06:01:26 +08:00
										 |  |  |   Vector evaluateError(const double& pk1, const double& qk, const double& qk1) const; | 
					
						
							| 
									
										
										
										
											2013-04-17 03:07:59 +08:00
										 |  |  | }; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-05-01 01:21:42 +08:00
										 |  |  | #include <gtsam_unstable/dynamics/SimpleHelicopter.h> | 
					
						
							| 
									
										
										
										
											2017-03-19 03:52:08 +08:00
										 |  |  | virtual class Reconstruction : gtsam::NoiseModelFactor {
 | 
					
						
							| 
									
										
										
										
											2013-05-01 01:21:42 +08:00
										 |  |  |   Reconstruction(size_t gKey1, size_t gKey, size_t xiKey, double h); | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2017-03-19 03:52:08 +08:00
										 |  |  |   Vector evaluateError(const gtsam::Pose3& gK1, const gtsam::Pose3& gK, Vector xiK) const; | 
					
						
							| 
									
										
										
										
											2013-05-01 01:21:42 +08:00
										 |  |  | }; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2017-03-19 03:52:08 +08:00
										 |  |  | virtual class DiscreteEulerPoincareHelicopter : gtsam::NoiseModelFactor {
 | 
					
						
							| 
									
										
										
										
											2013-05-01 01:21:42 +08:00
										 |  |  |   DiscreteEulerPoincareHelicopter(size_t xiKey, size_t xiKey_1, size_t gKey, | 
					
						
							|  |  |  |       double h, Matrix Inertia, Vector Fu, double m); | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2017-03-19 03:52:08 +08:00
										 |  |  |   Vector evaluateError(Vector xiK, Vector xiK_1, const gtsam::Pose3& gK) const; | 
					
						
							| 
									
										
										
										
											2013-05-01 01:21:42 +08:00
										 |  |  | }; | 
					
						
							| 
									
										
										
										
											2013-04-17 03:07:59 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2012-08-03 03:57:10 +08:00
										 |  |  | //************************************************************************* | 
					
						
							| 
									
										
										
										
											2012-09-21 22:19:57 +08:00
										 |  |  | // nonlinear | 
					
						
							|  |  |  | //************************************************************************* | 
					
						
							| 
									
										
										
										
											2019-03-08 03:25:05 +08:00
										 |  |  | #include <gtsam_unstable/nonlinear/FixedLagSmoother.h> | 
					
						
							|  |  |  | class FixedLagSmootherKeyTimestampMapValue {
 | 
					
						
							|  |  |  |   FixedLagSmootherKeyTimestampMapValue(size_t key, double timestamp); | 
					
						
							|  |  |  |   FixedLagSmootherKeyTimestampMapValue(const gtsam::FixedLagSmootherKeyTimestampMapValue& other); | 
					
						
							|  |  |  | }; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | class FixedLagSmootherKeyTimestampMap {
 | 
					
						
							|  |  |  |   FixedLagSmootherKeyTimestampMap(); | 
					
						
							|  |  |  |   FixedLagSmootherKeyTimestampMap(const gtsam::FixedLagSmootherKeyTimestampMap& other); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   // Note: no print function | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   // common STL methods | 
					
						
							|  |  |  |   size_t size() const; | 
					
						
							|  |  |  |   bool empty() const; | 
					
						
							|  |  |  |   void clear(); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   double at(const size_t key) const; | 
					
						
							|  |  |  |   void insert(const gtsam::FixedLagSmootherKeyTimestampMapValue& value); | 
					
						
							|  |  |  | }; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | class FixedLagSmootherResult {
 | 
					
						
							|  |  |  |   size_t getIterations() const; | 
					
						
							|  |  |  |   size_t getNonlinearVariables() const; | 
					
						
							|  |  |  |   size_t getLinearVariables() const; | 
					
						
							|  |  |  |   double getError() const; | 
					
						
							|  |  |  | }; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | #include <gtsam_unstable/nonlinear/FixedLagSmoother.h> | 
					
						
							|  |  |  | virtual class FixedLagSmoother {
 | 
					
						
							|  |  |  |   void print(string s) const; | 
					
						
							|  |  |  |   bool equals(const gtsam::FixedLagSmoother& rhs, double tol) const; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   gtsam::FixedLagSmootherKeyTimestampMap timestamps() const; | 
					
						
							|  |  |  |   double smootherLag() const; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2022-01-30 05:13:23 +08:00
										 |  |  |   gtsam::FixedLagSmootherResult update(const gtsam::NonlinearFactorGraph &newFactors, | 
					
						
							|  |  |  |                                        const gtsam::Values &newTheta, | 
					
						
							|  |  |  |                                        const gtsam::FixedLagSmootherKeyTimestampMap ×tamps); | 
					
						
							| 
									
										
										
										
											2022-01-22 22:35:53 +08:00
										 |  |  |   gtsam::FixedLagSmootherResult update(const gtsam::NonlinearFactorGraph &newFactors, | 
					
						
							|  |  |  |                                        const gtsam::Values &newTheta, | 
					
						
							|  |  |  |                                        const gtsam::FixedLagSmootherKeyTimestampMap ×tamps, | 
					
						
							| 
									
										
										
										
											2022-01-30 05:13:23 +08:00
										 |  |  |                                        const gtsam::FactorIndices &factorsToRemove); | 
					
						
							| 
									
										
										
										
											2019-03-08 03:25:05 +08:00
										 |  |  |   gtsam::Values calculateEstimate() const; | 
					
						
							|  |  |  | }; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | #include <gtsam_unstable/nonlinear/BatchFixedLagSmoother.h> | 
					
						
							|  |  |  | virtual class BatchFixedLagSmoother : gtsam::FixedLagSmoother {
 | 
					
						
							|  |  |  |   BatchFixedLagSmoother(); | 
					
						
							|  |  |  |   BatchFixedLagSmoother(double smootherLag); | 
					
						
							|  |  |  |   BatchFixedLagSmoother(double smootherLag, const gtsam::LevenbergMarquardtParams& params); | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2022-01-30 06:31:07 +08:00
										 |  |  |   void print(string s = "BatchFixedLagSmoother:\n") const; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2019-03-08 03:25:05 +08:00
										 |  |  |   gtsam::LevenbergMarquardtParams params() const; | 
					
						
							|  |  |  |   template <VALUE = {gtsam::Point2, gtsam::Rot2, gtsam::Pose2, gtsam::Point3,
 | 
					
						
							|  |  |  |                      gtsam::Rot3, gtsam::Pose3, gtsam::Cal3_S2, gtsam::Cal3DS2, | 
					
						
							|  |  |  |                      Vector, Matrix}> | 
					
						
							|  |  |  |   VALUE calculateEstimate(size_t key) const; | 
					
						
							|  |  |  | }; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | #include <gtsam_unstable/nonlinear/IncrementalFixedLagSmoother.h> | 
					
						
							|  |  |  | virtual class IncrementalFixedLagSmoother : gtsam::FixedLagSmoother {
 | 
					
						
							|  |  |  |   IncrementalFixedLagSmoother(); | 
					
						
							|  |  |  |   IncrementalFixedLagSmoother(double smootherLag); | 
					
						
							|  |  |  |   IncrementalFixedLagSmoother(double smootherLag, const gtsam::ISAM2Params& params); | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2022-01-30 06:31:07 +08:00
										 |  |  |   void print(string s = "IncrementalFixedLagSmoother:\n") const; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2019-03-08 03:25:05 +08:00
										 |  |  |   gtsam::ISAM2Params params() const; | 
					
						
							| 
									
										
										
										
											2022-01-22 22:35:53 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   gtsam::NonlinearFactorGraph getFactors() const; | 
					
						
							| 
									
										
										
										
											2022-01-30 06:31:07 +08:00
										 |  |  |   gtsam::ISAM2 getISAM2() const; | 
					
						
							| 
									
										
										
										
											2019-03-08 03:25:05 +08:00
										 |  |  | }; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | #include <gtsam_unstable/nonlinear/ConcurrentFilteringAndSmoothing.h> | 
					
						
							|  |  |  | virtual class ConcurrentFilter {
 | 
					
						
							|  |  |  |   void print(string s) const; | 
					
						
							|  |  |  |   bool equals(const gtsam::ConcurrentFilter& rhs, double tol) const; | 
					
						
							|  |  |  | }; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | virtual class ConcurrentSmoother {
 | 
					
						
							|  |  |  |   void print(string s) const; | 
					
						
							|  |  |  |   bool equals(const gtsam::ConcurrentSmoother& rhs, double tol) const; | 
					
						
							|  |  |  | }; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | // Synchronize function | 
					
						
							|  |  |  | void synchronize(gtsam::ConcurrentFilter& filter, gtsam::ConcurrentSmoother& smoother); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | #include <gtsam_unstable/nonlinear/ConcurrentBatchFilter.h> | 
					
						
							|  |  |  | class ConcurrentBatchFilterResult {
 | 
					
						
							|  |  |  |   size_t getIterations() const; | 
					
						
							|  |  |  |   size_t getLambdas() const; | 
					
						
							|  |  |  |   size_t getNonlinearVariables() const; | 
					
						
							|  |  |  |   size_t getLinearVariables() const; | 
					
						
							|  |  |  |   double getError() const; | 
					
						
							|  |  |  | }; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | virtual class ConcurrentBatchFilter : gtsam::ConcurrentFilter {
 | 
					
						
							|  |  |  |   ConcurrentBatchFilter(); | 
					
						
							|  |  |  |   ConcurrentBatchFilter(const gtsam::LevenbergMarquardtParams& parameters); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   gtsam::NonlinearFactorGraph getFactors() const; | 
					
						
							|  |  |  |   gtsam::Values getLinearizationPoint() const; | 
					
						
							|  |  |  |   gtsam::Ordering getOrdering() const; | 
					
						
							|  |  |  |   gtsam::VectorValues getDelta() const; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   gtsam::ConcurrentBatchFilterResult update(); | 
					
						
							|  |  |  |   gtsam::ConcurrentBatchFilterResult update(const gtsam::NonlinearFactorGraph& newFactors); | 
					
						
							|  |  |  |   gtsam::ConcurrentBatchFilterResult update(const gtsam::NonlinearFactorGraph& newFactors, const gtsam::Values& newTheta); | 
					
						
							|  |  |  |   gtsam::ConcurrentBatchFilterResult update(const gtsam::NonlinearFactorGraph& newFactors, const gtsam::Values& newTheta, const gtsam::KeyList& keysToMove); | 
					
						
							|  |  |  |   gtsam::Values calculateEstimate() const; | 
					
						
							|  |  |  | }; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | #include <gtsam_unstable/nonlinear/ConcurrentBatchSmoother.h> | 
					
						
							|  |  |  | class ConcurrentBatchSmootherResult {
 | 
					
						
							|  |  |  |   size_t getIterations() const; | 
					
						
							|  |  |  |   size_t getLambdas() const; | 
					
						
							|  |  |  |   size_t getNonlinearVariables() const; | 
					
						
							|  |  |  |   size_t getLinearVariables() const; | 
					
						
							|  |  |  |   double getError() const; | 
					
						
							|  |  |  | }; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | virtual class ConcurrentBatchSmoother : gtsam::ConcurrentSmoother {
 | 
					
						
							|  |  |  |   ConcurrentBatchSmoother(); | 
					
						
							|  |  |  |   ConcurrentBatchSmoother(const gtsam::LevenbergMarquardtParams& parameters); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   gtsam::NonlinearFactorGraph getFactors() const; | 
					
						
							|  |  |  |   gtsam::Values getLinearizationPoint() const; | 
					
						
							|  |  |  |   gtsam::Ordering getOrdering() const; | 
					
						
							|  |  |  |   gtsam::VectorValues getDelta() const; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   gtsam::ConcurrentBatchSmootherResult update(); | 
					
						
							|  |  |  |   gtsam::ConcurrentBatchSmootherResult update(const gtsam::NonlinearFactorGraph& newFactors); | 
					
						
							|  |  |  |   gtsam::ConcurrentBatchSmootherResult update(const gtsam::NonlinearFactorGraph& newFactors, const gtsam::Values& newTheta); | 
					
						
							|  |  |  |   gtsam::Values calculateEstimate() const; | 
					
						
							|  |  |  | }; | 
					
						
							| 
									
										
										
										
											2013-04-16 03:54:46 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2012-09-21 22:19:57 +08:00
										 |  |  | //************************************************************************* | 
					
						
							|  |  |  | // slam | 
					
						
							| 
									
										
										
										
											2012-08-03 03:57:10 +08:00
										 |  |  | //************************************************************************* | 
					
						
							| 
									
										
										
										
											2012-08-20 22:25:10 +08:00
										 |  |  | #include <gtsam_unstable/slam/RelativeElevationFactor.h> | 
					
						
							| 
									
										
										
										
											2017-03-19 03:52:08 +08:00
										 |  |  | virtual class RelativeElevationFactor: gtsam::NoiseModelFactor {
 | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  |   RelativeElevationFactor(); | 
					
						
							|  |  |  |   RelativeElevationFactor(size_t poseKey, size_t pointKey, double measured, | 
					
						
							|  |  |  |       const gtsam::noiseModel::Base* model); | 
					
						
							| 
									
										
										
										
											2012-08-20 22:25:10 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  |   double measured() const; | 
					
						
							| 
									
										
										
										
											2017-03-19 03:52:08 +08:00
										 |  |  |   //void print(string s) const; | 
					
						
							| 
									
										
										
										
											2012-08-20 22:25:10 +08:00
										 |  |  | }; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2012-09-19 01:48:18 +08:00
										 |  |  | #include <gtsam_unstable/slam/DummyFactor.h> | 
					
						
							|  |  |  | virtual class DummyFactor : gtsam::NonlinearFactor {
 | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  |   DummyFactor(size_t key1, size_t dim1, size_t key2, size_t dim2); | 
					
						
							| 
									
										
										
										
											2012-09-19 01:48:18 +08:00
										 |  |  | }; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-05-08 21:23:39 +08:00
										 |  |  | #include <gtsam_unstable/slam/InvDepthFactorVariant1.h> | 
					
						
							| 
									
										
										
										
											2017-03-19 03:52:08 +08:00
										 |  |  | virtual class InvDepthFactorVariant1 : gtsam::NoiseModelFactor {
 | 
					
						
							| 
									
										
										
										
											2013-05-08 21:23:39 +08:00
										 |  |  |   InvDepthFactorVariant1(size_t poseKey, size_t landmarkKey, const gtsam::Point2& measured, const gtsam::Cal3_S2* K, const gtsam::noiseModel::Base* model); | 
					
						
							|  |  |  | }; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | #include <gtsam_unstable/slam/InvDepthFactorVariant2.h> | 
					
						
							| 
									
										
										
										
											2017-03-19 03:52:08 +08:00
										 |  |  | virtual class InvDepthFactorVariant2 : gtsam::NoiseModelFactor {
 | 
					
						
							| 
									
										
										
										
											2013-05-08 21:23:39 +08:00
										 |  |  |   InvDepthFactorVariant2(size_t poseKey, size_t landmarkKey, const gtsam::Point2& measured, const gtsam::Cal3_S2* K, const gtsam::Point3& referencePoint, const gtsam::noiseModel::Base* model); | 
					
						
							|  |  |  | }; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | #include <gtsam_unstable/slam/InvDepthFactorVariant3.h> | 
					
						
							| 
									
										
										
										
											2017-03-19 03:52:08 +08:00
										 |  |  | virtual class InvDepthFactorVariant3a : gtsam::NoiseModelFactor {
 | 
					
						
							| 
									
										
										
										
											2013-05-08 21:23:39 +08:00
										 |  |  |   InvDepthFactorVariant3a(size_t poseKey, size_t landmarkKey, const gtsam::Point2& measured, const gtsam::Cal3_S2* K, const gtsam::noiseModel::Base* model); | 
					
						
							|  |  |  | }; | 
					
						
							| 
									
										
										
										
											2017-03-19 03:52:08 +08:00
										 |  |  | virtual class InvDepthFactorVariant3b : gtsam::NoiseModelFactor {
 | 
					
						
							| 
									
										
										
										
											2013-05-08 21:23:39 +08:00
										 |  |  |   InvDepthFactorVariant3b(size_t poseKey1, size_t poseKey2, size_t landmarkKey, const gtsam::Point2& measured, const gtsam::Cal3_S2* K, const gtsam::noiseModel::Base* model); | 
					
						
							|  |  |  | }; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-08-03 00:04:17 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-05-21 07:28:38 +08:00
										 |  |  | #include <gtsam_unstable/slam/Mechanization_bRn2.h> | 
					
						
							|  |  |  | class Mechanization_bRn2 {
 | 
					
						
							|  |  |  |   Mechanization_bRn2(); | 
					
						
							|  |  |  |   Mechanization_bRn2(gtsam::Rot3& initial_bRn, Vector initial_x_g, | 
					
						
							|  |  |  |       Vector initial_x_a); | 
					
						
							|  |  |  |   Vector b_g(double g_e); | 
					
						
							|  |  |  |   gtsam::Rot3 bRn(); | 
					
						
							|  |  |  |   Vector x_g(); | 
					
						
							|  |  |  |   Vector x_a(); | 
					
						
							|  |  |  |   static gtsam::Mechanization_bRn2 initialize(Matrix U, Matrix F, double g_e); | 
					
						
							|  |  |  |   gtsam::Mechanization_bRn2 correct(Vector dx) const; | 
					
						
							|  |  |  |   gtsam::Mechanization_bRn2 integrate(Vector u, double dt) const; | 
					
						
							| 
									
										
										
										
											2017-03-19 03:52:08 +08:00
										 |  |  |   //void print(string s) const; | 
					
						
							| 
									
										
										
										
											2013-05-21 07:28:38 +08:00
										 |  |  | }; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | #include <gtsam_unstable/slam/AHRS.h> | 
					
						
							|  |  |  | class AHRS {
 | 
					
						
							|  |  |  |   AHRS(Matrix U, Matrix F, double g_e); | 
					
						
							|  |  |  |   pair<gtsam::Mechanization_bRn2, gtsam::GaussianDensity*> initialize(double g_e); | 
					
						
							|  |  |  |   pair<gtsam::Mechanization_bRn2, gtsam::GaussianDensity*> integrate(const gtsam::Mechanization_bRn2& mech, gtsam::GaussianDensity* state, Vector u, double dt); | 
					
						
							|  |  |  |   pair<gtsam::Mechanization_bRn2, gtsam::GaussianDensity*> aid(const gtsam::Mechanization_bRn2& mech, gtsam::GaussianDensity* state, Vector f, bool Farrel); | 
					
						
							|  |  |  |   pair<gtsam::Mechanization_bRn2, gtsam::GaussianDensity*> aidGeneral(const gtsam::Mechanization_bRn2& mech, gtsam::GaussianDensity* state, Vector f, Vector f_expected, const gtsam::Rot3& increment); | 
					
						
							| 
									
										
										
										
											2017-03-19 03:52:08 +08:00
										 |  |  |   //void print(string s) const; | 
					
						
							| 
									
										
										
										
											2013-05-21 07:28:38 +08:00
										 |  |  | }; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2014-05-05 22:14:56 +08:00
										 |  |  | // Tectonic SAM Factors | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | #include <gtsam_unstable/slam/TSAMFactors.h> | 
					
						
							| 
									
										
										
										
											2022-12-24 22:35:45 +08:00
										 |  |  | //typedef gtsam::NoiseModelFactorN<gtsam::Pose2, gtsam::Point2> NLPosePose; | 
					
						
							| 
									
										
										
										
											2014-05-05 22:14:56 +08:00
										 |  |  | virtual class DeltaFactor : gtsam::NoiseModelFactor {
 | 
					
						
							|  |  |  |   DeltaFactor(size_t i, size_t j, const gtsam::Point2& measured, | 
					
						
							|  |  |  |       const gtsam::noiseModel::Base* noiseModel); | 
					
						
							| 
									
										
										
										
											2017-03-19 03:52:08 +08:00
										 |  |  |   //void print(string s) const; | 
					
						
							| 
									
										
										
										
											2014-05-05 22:14:56 +08:00
										 |  |  | }; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2022-12-24 22:35:45 +08:00
										 |  |  | //typedef gtsam::NoiseModelFactorN<gtsam::Pose2, gtsam::Pose2, gtsam::Pose2, | 
					
						
							| 
									
										
										
										
											2014-05-05 22:14:56 +08:00
										 |  |  | //    gtsam::Point2> NLPosePosePosePoint; | 
					
						
							|  |  |  | virtual class DeltaFactorBase : gtsam::NoiseModelFactor {
 | 
					
						
							|  |  |  |   DeltaFactorBase(size_t b1, size_t i, size_t b2, size_t j, | 
					
						
							|  |  |  |       const gtsam::Point2& measured, const gtsam::noiseModel::Base* noiseModel); | 
					
						
							| 
									
										
										
										
											2017-03-19 03:52:08 +08:00
										 |  |  |   //void print(string s) const; | 
					
						
							| 
									
										
										
										
											2014-05-05 22:14:56 +08:00
										 |  |  | }; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2022-12-24 22:35:45 +08:00
										 |  |  | //typedef gtsam::NoiseModelFactorN<gtsam::Pose2, gtsam::Pose2, gtsam::Pose2, | 
					
						
							| 
									
										
										
										
											2014-05-05 22:14:56 +08:00
										 |  |  | //    gtsam::Pose2> NLPosePosePosePose; | 
					
						
							|  |  |  | virtual class OdometryFactorBase : gtsam::NoiseModelFactor {
 | 
					
						
							|  |  |  |   OdometryFactorBase(size_t b1, size_t i, size_t b2, size_t j, | 
					
						
							|  |  |  |       const gtsam::Pose2& measured, const gtsam::noiseModel::Base* noiseModel); | 
					
						
							| 
									
										
										
										
											2017-03-19 03:52:08 +08:00
										 |  |  |   //void print(string s) const; | 
					
						
							| 
									
										
										
										
											2014-05-05 22:14:56 +08:00
										 |  |  | }; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2014-07-02 04:03:35 +08:00
										 |  |  | #include <gtsam/geometry/Cal3DS2.h> | 
					
						
							| 
									
										
										
										
											2014-08-13 03:54:12 +08:00
										 |  |  | #include <gtsam_unstable/slam/ProjectionFactorPPP.h> | 
					
						
							| 
									
										
										
										
											2014-07-02 04:03:35 +08:00
										 |  |  | template<POSE, LANDMARK, CALIBRATION> | 
					
						
							| 
									
										
										
										
											2014-08-13 03:54:12 +08:00
										 |  |  | virtual class ProjectionFactorPPP : gtsam::NoiseModelFactor {
 | 
					
						
							|  |  |  |   ProjectionFactorPPP(const gtsam::Point2& measured, const gtsam::noiseModel::Base* noiseModel, | 
					
						
							| 
									
										
										
										
											2014-07-02 04:03:35 +08:00
										 |  |  |     size_t poseKey, size_t transformKey, size_t pointKey, const CALIBRATION* k); | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2014-08-13 03:54:12 +08:00
										 |  |  |   ProjectionFactorPPP(const gtsam::Point2& measured, const gtsam::noiseModel::Base* noiseModel, | 
					
						
							| 
									
										
										
										
											2014-07-02 04:03:35 +08:00
										 |  |  |       size_t poseKey, size_t transformKey, size_t pointKey, const CALIBRATION* k, bool throwCheirality, bool verboseCheirality); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   gtsam::Point2 measured() const; | 
					
						
							|  |  |  |   CALIBRATION* calibration() const; | 
					
						
							|  |  |  |   bool verboseCheirality() const; | 
					
						
							|  |  |  |   bool throwCheirality() const; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   // enabling serialization functionality | 
					
						
							|  |  |  |   void serialize() const; | 
					
						
							|  |  |  | }; | 
					
						
							| 
									
										
										
										
											2014-08-13 03:54:12 +08:00
										 |  |  | typedef gtsam::ProjectionFactorPPP<gtsam::Pose3, gtsam::Point3, gtsam::Cal3_S2> ProjectionFactorPPPCal3_S2; | 
					
						
							|  |  |  | typedef gtsam::ProjectionFactorPPP<gtsam::Pose3, gtsam::Point3, gtsam::Cal3DS2> ProjectionFactorPPPCal3DS2; | 
					
						
							| 
									
										
										
										
											2014-07-02 04:03:35 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2014-08-13 03:29:05 +08:00
										 |  |  | #include <gtsam_unstable/slam/ProjectionFactorPPPC.h> | 
					
						
							| 
									
										
										
										
											2014-07-02 04:03:35 +08:00
										 |  |  | template<POSE, LANDMARK, CALIBRATION> | 
					
						
							| 
									
										
										
										
											2014-08-13 03:29:05 +08:00
										 |  |  | virtual class ProjectionFactorPPPC : gtsam::NoiseModelFactor {
 | 
					
						
							|  |  |  |   ProjectionFactorPPPC(const gtsam::Point2& measured, const gtsam::noiseModel::Base* noiseModel, | 
					
						
							| 
									
										
										
										
											2014-07-02 04:03:35 +08:00
										 |  |  |     size_t poseKey, size_t transformKey, size_t pointKey, size_t calibKey); | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2014-08-13 03:29:05 +08:00
										 |  |  |   ProjectionFactorPPPC(const gtsam::Point2& measured, const gtsam::noiseModel::Base* noiseModel, | 
					
						
							| 
									
										
										
										
											2014-07-02 04:03:35 +08:00
										 |  |  |       size_t poseKey, size_t transformKey, size_t pointKey, size_t calibKey, bool throwCheirality, bool verboseCheirality); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   gtsam::Point2 measured() const; | 
					
						
							|  |  |  |   bool verboseCheirality() const; | 
					
						
							|  |  |  |   bool throwCheirality() const; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   // enabling serialization functionality | 
					
						
							|  |  |  |   void serialize() const; | 
					
						
							|  |  |  | }; | 
					
						
							| 
									
										
										
										
											2014-08-13 03:29:05 +08:00
										 |  |  | typedef gtsam::ProjectionFactorPPPC<gtsam::Pose3, gtsam::Point3, gtsam::Cal3_S2> ProjectionFactorPPPCCal3_S2; | 
					
						
							|  |  |  | typedef gtsam::ProjectionFactorPPPC<gtsam::Pose3, gtsam::Point3, gtsam::Cal3DS2> ProjectionFactorPPPCCal3DS2; | 
					
						
							| 
									
										
										
										
											2014-07-02 04:03:35 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2022-04-05 13:51:03 +08:00
										 |  |  | #include <gtsam_unstable/slam/ProjectionFactorRollingShutter.h> | 
					
						
							|  |  |  | virtual class ProjectionFactorRollingShutter : gtsam::NoiseModelFactor {
 | 
					
						
							|  |  |  |   ProjectionFactorRollingShutter(const gtsam::Point2& measured, double alpha, const gtsam::noiseModel::Base* noiseModel, | 
					
						
							|  |  |  |       size_t poseKey_a, size_t poseKey_b, size_t pointKey, const gtsam::Cal3_S2* K); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   ProjectionFactorRollingShutter(const gtsam::Point2& measured, double alpha, const gtsam::noiseModel::Base* noiseModel, | 
					
						
							|  |  |  |     size_t poseKey_a, size_t poseKey_b, size_t pointKey, const gtsam::Cal3_S2* K, gtsam::Pose3& body_P_sensor); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   ProjectionFactorRollingShutter(const gtsam::Point2& measured, double alpha, const gtsam::noiseModel::Base* noiseModel, | 
					
						
							|  |  |  |         size_t poseKey_a, size_t poseKey_b, size_t pointKey, const gtsam::Cal3_S2* K, bool throwCheirality, | 
					
						
							|  |  |  |         bool verboseCheirality); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   ProjectionFactorRollingShutter(const gtsam::Point2& measured, double alpha, const gtsam::noiseModel::Base* noiseModel, | 
					
						
							|  |  |  |       size_t poseKey_a, size_t poseKey_b, size_t pointKey, const gtsam::Cal3_S2* K, bool throwCheirality, | 
					
						
							|  |  |  |       bool verboseCheirality, gtsam::Pose3& body_P_sensor); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   gtsam::Point2 measured() const; | 
					
						
							|  |  |  |   double alpha() const; | 
					
						
							|  |  |  |   gtsam::Cal3_S2* calibration() const; | 
					
						
							|  |  |  |   bool verboseCheirality() const; | 
					
						
							|  |  |  |   bool throwCheirality() const; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   // enabling serialization functionality | 
					
						
							|  |  |  |   void serialize() const; | 
					
						
							|  |  |  | }; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2012-08-03 03:57:10 +08:00
										 |  |  | } //\namespace gtsam |