add new type for vector of Rot3's
							parent
							
								
									055e027632
								
							
						
					
					
						commit
						20622c2579
					
				|  | @ -322,7 +322,15 @@ template <T = {gtsam::Point2, gtsam::Rot2, gtsam::Pose2, gtsam::Point3, | |||
| virtual class KarcherMeanFactor : gtsam::NonlinearFactor { | ||||
|   KarcherMeanFactor(const gtsam::KeyVector& keys); | ||||
| }; | ||||
| const gtsam::Rot3 FindKarcherMean<gtsam::Rot3>(const std::vector<gtsam::Rot3>& rotations); | ||||
|    | ||||
| class Rot3Vector { | ||||
|   Rot3Vector(); | ||||
| 
 | ||||
|   // structure specific methods | ||||
|   gtsam::Rot3 at(size_t i) const; | ||||
|   void push_back(const gtsam::Rot3& R); | ||||
| }; | ||||
| const gtsam::Rot3 FindKarcherMean<gtsam::Rot3>(const Rot3Vector& rotations); | ||||
| 
 | ||||
| #include <gtsam/slam/FrobeniusFactor.h> | ||||
| gtsam::noiseModel::Isotropic* ConvertNoiseModel(gtsam::noiseModel::Base* model, | ||||
|  |  | |||
		Loading…
	
		Reference in New Issue