Moved Point2Vector wrapper from gtsam_unstable.h to gtsam.h
parent
b52ced7a09
commit
13dcc977f2
26
gtsam.h
26
gtsam.h
|
@ -288,6 +288,32 @@ class Point2 {
|
|||
void serialize() const;
|
||||
};
|
||||
|
||||
// std::vector<gtsam::Point2>
|
||||
class Point2Vector
|
||||
{
|
||||
// Constructors
|
||||
Point2Vector();
|
||||
Point2Vector(const gtsam::Point2Vector& v);
|
||||
|
||||
//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::Point2 at(size_t n) const;
|
||||
gtsam::Point2 front() const;
|
||||
gtsam::Point2 back() const;
|
||||
|
||||
//Modifiers
|
||||
void assign(size_t n, const gtsam::Point2& u);
|
||||
void push_back(const gtsam::Point2& x);
|
||||
void pop_back();
|
||||
};
|
||||
|
||||
class StereoPoint2 {
|
||||
// Standard Constructors
|
||||
StereoPoint2();
|
||||
|
|
|
@ -192,9 +192,11 @@ private:
|
|||
}
|
||||
|
||||
/// @}
|
||||
|
||||
};
|
||||
|
||||
// For MATLAB wrapper
|
||||
typedef std::vector<Point2> Point2Vector;
|
||||
|
||||
/// multiply with scalar
|
||||
inline Point2 operator*(double s, const Point2& p) {return p*s;}
|
||||
|
||||
|
|
|
@ -128,7 +128,6 @@ public:
|
|||
};
|
||||
|
||||
typedef std::vector<SimPolygon2D> SimPolygon2DVector;
|
||||
typedef std::vector<Point2> Point2Vector;
|
||||
|
||||
} //\namespace gtsam
|
||||
|
||||
|
|
|
@ -8,6 +8,7 @@ class gtsam::Vector6;
|
|||
class gtsam::LieScalar;
|
||||
class gtsam::LieVector;
|
||||
class gtsam::Point2;
|
||||
class gtsam::Point2Vector;
|
||||
class gtsam::Rot2;
|
||||
class gtsam::Pose2;
|
||||
class gtsam::Point3;
|
||||
|
@ -159,32 +160,6 @@ class BearingS2 {
|
|||
void serializable() const; // enabling serialization functionality
|
||||
};
|
||||
|
||||
// std::vector<gtsam::Point2>
|
||||
class Point2Vector
|
||||
{
|
||||
// Constructors
|
||||
Point2Vector();
|
||||
Point2Vector(const gtsam::Point2Vector& v);
|
||||
|
||||
//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::Point2 at(size_t n) const;
|
||||
gtsam::Point2 front() const;
|
||||
gtsam::Point2 back() const;
|
||||
|
||||
//Modifiers
|
||||
void assign(size_t n, const gtsam::Point2& u);
|
||||
void push_back(const gtsam::Point2& x);
|
||||
void pop_back();
|
||||
};
|
||||
|
||||
#include <gtsam_unstable/geometry/SimWall2D.h>
|
||||
class SimWall2D {
|
||||
SimWall2D();
|
||||
|
|
Loading…
Reference in New Issue