Added Pose3Vector
							parent
							
								
									39deb92314
								
							
						
					
					
						commit
						cd077c336d
					
				
							
								
								
									
										10
									
								
								gtsam.h
								
								
								
								
							
							
						
						
									
										10
									
								
								gtsam.h
								
								
								
								
							| 
						 | 
					@ -576,6 +576,16 @@ class Pose3 {
 | 
				
			||||||
  void serialize() const;
 | 
					  void serialize() const;
 | 
				
			||||||
};
 | 
					};
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					// std::vector<gtsam::Pose3>
 | 
				
			||||||
 | 
					class Pose3Vector
 | 
				
			||||||
 | 
					{
 | 
				
			||||||
 | 
					  Pose3Vector();
 | 
				
			||||||
 | 
					  size_t size() const;
 | 
				
			||||||
 | 
					  bool empty() const;
 | 
				
			||||||
 | 
					  gtsam::Pose3 at(size_t n) const;
 | 
				
			||||||
 | 
					  void push_back(const gtsam::Pose3& x);
 | 
				
			||||||
 | 
					};
 | 
				
			||||||
 | 
					
 | 
				
			||||||
#include <gtsam/geometry/Unit3.h>
 | 
					#include <gtsam/geometry/Unit3.h>
 | 
				
			||||||
class Unit3 {
 | 
					class Unit3 {
 | 
				
			||||||
  // Standard Constructors
 | 
					  // Standard Constructors
 | 
				
			||||||
| 
						 | 
					
 | 
				
			||||||
| 
						 | 
					@ -322,6 +322,9 @@ inline Matrix wedge<Pose3>(const Vector& xi) {
 | 
				
			||||||
typedef std::pair<Point3, Point3> Point3Pair;
 | 
					typedef std::pair<Point3, Point3> Point3Pair;
 | 
				
			||||||
GTSAM_EXPORT boost::optional<Pose3> align(const std::vector<Point3Pair>& pairs);
 | 
					GTSAM_EXPORT boost::optional<Pose3> align(const std::vector<Point3Pair>& pairs);
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					// For MATLAB wrapper
 | 
				
			||||||
 | 
					typedef std::vector<Pose3> Pose3Vector;
 | 
				
			||||||
 | 
					
 | 
				
			||||||
template<>
 | 
					template<>
 | 
				
			||||||
struct traits<Pose3> : public internal::LieGroupTraits<Pose3> {};
 | 
					struct traits<Pose3> : public internal::LieGroupTraits<Pose3> {};
 | 
				
			||||||
 | 
					
 | 
				
			||||||
| 
						 | 
					
 | 
				
			||||||
		Loading…
	
		Reference in New Issue