Added Pose3Vector

release/4.3a0
dellaert 2015-05-03 17:32:13 -07:00
parent 39deb92314
commit cd077c336d
2 changed files with 13 additions and 0 deletions

10
gtsam.h
View File

@ -576,6 +576,16 @@ class Pose3 {
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>
class Unit3 {
// Standard Constructors

View File

@ -322,6 +322,9 @@ inline Matrix wedge<Pose3>(const Vector& xi) {
typedef std::pair<Point3, Point3> Point3Pair;
GTSAM_EXPORT boost::optional<Pose3> align(const std::vector<Point3Pair>& pairs);
// For MATLAB wrapper
typedef std::vector<Pose3> Pose3Vector;
template<>
struct traits<Pose3> : public internal::LieGroupTraits<Pose3> {};