| 
									
										
										
										
											2010-10-14 12:54:38 +08:00
										 |  |  | /* ----------------------------------------------------------------------------
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |  * GTSAM Copyright 2010, Georgia Tech Research Corporation,  | 
					
						
							|  |  |  |  * Atlanta, Georgia 30332-0415 | 
					
						
							|  |  |  |  * All Rights Reserved | 
					
						
							|  |  |  |  * Authors: Frank Dellaert, et al. (see THANKS for the full author list) | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |  * See LICENSE for the license information | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |  * -------------------------------------------------------------------------- */ | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-01-23 01:36:57 +08:00
										 |  |  | /*
 | 
					
						
							|  |  |  |  * SharedDiagonal.h | 
					
						
							|  |  |  |  * @brief Class that wraps a shared noise model with diagonal covariance | 
					
						
							|  |  |  |  * @Author: Frank Dellaert | 
					
						
							|  |  |  |  * Created on: Jan 22, 2010 | 
					
						
							|  |  |  |  */ | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | #pragma once
 | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-08-20 01:23:19 +08:00
										 |  |  | #include <gtsam/linear/NoiseModel.h>
 | 
					
						
							| 
									
										
										
										
											2010-01-23 01:36:57 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | namespace gtsam { // note, deliberately not in noiseModel namespace
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 	// A useful convenience class to refer to a shared Diagonal model
 | 
					
						
							|  |  |  | 	// There are (somewhat dangerous) constructors from Vector and pair<size_t,double>
 | 
					
						
							|  |  |  | 	// that call Sigmas and Sigma, respectively.
 | 
					
						
							|  |  |  | 	struct SharedDiagonal: public noiseModel::Diagonal::shared_ptr { | 
					
						
							|  |  |  | 		SharedDiagonal() { | 
					
						
							|  |  |  | 		} | 
					
						
							|  |  |  | 		SharedDiagonal(const noiseModel::Diagonal::shared_ptr& p) : | 
					
						
							|  |  |  | 			noiseModel::Diagonal::shared_ptr(p) { | 
					
						
							|  |  |  | 		} | 
					
						
							|  |  |  | 		SharedDiagonal(const noiseModel::Constrained::shared_ptr& p) : | 
					
						
							|  |  |  | 			noiseModel::Diagonal::shared_ptr(p) { | 
					
						
							|  |  |  | 		} | 
					
						
							|  |  |  | 		SharedDiagonal(const noiseModel::Isotropic::shared_ptr& p) : | 
					
						
							|  |  |  | 			noiseModel::Diagonal::shared_ptr(p) { | 
					
						
							|  |  |  | 		} | 
					
						
							|  |  |  | 		SharedDiagonal(const noiseModel::Unit::shared_ptr& p) : | 
					
						
							|  |  |  | 			noiseModel::Diagonal::shared_ptr(p) { | 
					
						
							|  |  |  | 		} | 
					
						
							|  |  |  | 		SharedDiagonal(const Vector& sigmas) : | 
					
						
							|  |  |  | 			noiseModel::Diagonal::shared_ptr(noiseModel::Diagonal::Sigmas(sigmas)) { | 
					
						
							|  |  |  | 		} | 
					
						
							|  |  |  | 	}; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 	// TODO: make these the ones really used in unit tests
 | 
					
						
							|  |  |  | 	inline SharedDiagonal sharedSigmas(const Vector& sigmas) { | 
					
						
							|  |  |  | 		return noiseModel::Diagonal::Sigmas(sigmas); | 
					
						
							|  |  |  | 	} | 
					
						
							| 
									
										
										
										
											2010-07-11 05:01:06 +08:00
										 |  |  | 	inline SharedDiagonal sharedSigma(size_t dim, double sigma) { | 
					
						
							| 
									
										
										
										
											2010-01-23 01:36:57 +08:00
										 |  |  | 		return noiseModel::Isotropic::Sigma(dim, sigma); | 
					
						
							|  |  |  | 	} | 
					
						
							| 
									
										
										
										
											2010-07-11 05:01:06 +08:00
										 |  |  | 	inline SharedDiagonal sharedPrecisions(const Vector& precisions) { | 
					
						
							|  |  |  | 	  return noiseModel::Diagonal::Precisions(precisions); | 
					
						
							|  |  |  | 	} | 
					
						
							|  |  |  | 	inline SharedDiagonal sharedPrecision(size_t dim, double precision) { | 
					
						
							|  |  |  | 	  return noiseModel::Isotropic::Precision(dim, precision); | 
					
						
							|  |  |  | 	} | 
					
						
							| 
									
										
										
										
											2010-01-23 01:36:57 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | } |