move sim3 to stable version
parent
bbd7ed4f69
commit
0a2deab5b6
|
@ -15,7 +15,7 @@
|
||||||
* @author Paul Drews
|
* @author Paul Drews
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#include <gtsam_unstable/geometry/Similarity3.h>
|
#include <gtsam/geometry/Similarity3.h>
|
||||||
|
|
||||||
#include <gtsam/geometry/Pose3.h>
|
#include <gtsam/geometry/Pose3.h>
|
||||||
#include <gtsam/base/Manifold.h>
|
#include <gtsam/base/Manifold.h>
|
|
@ -1058,6 +1058,29 @@ class PinholeCamera {
|
||||||
void serialize() const;
|
void serialize() const;
|
||||||
};
|
};
|
||||||
|
|
||||||
|
|
||||||
|
#include <gtsam/geometry/Similarity3.h>
|
||||||
|
class PointPairs
|
||||||
|
{
|
||||||
|
PointPairs();
|
||||||
|
size_t size() const;
|
||||||
|
bool empty() const;
|
||||||
|
gtsam::Point3Pair at(size_t n) const;
|
||||||
|
void push_back(const gtsam::Point3Pair& point_pair);
|
||||||
|
};
|
||||||
|
|
||||||
|
class Similarity3 {
|
||||||
|
Similarity3();
|
||||||
|
Similarity3(double s);
|
||||||
|
Similarity3(const gtsam::Rot3& R, const gtsam::Point3& t, double s);
|
||||||
|
Similarity3(const Matrix& R, const Vector& t, double s);
|
||||||
|
Similarity3(const Matrix& T);
|
||||||
|
|
||||||
|
static Similarity3 Align(const gtsam::PointPairs & abPointPairs);
|
||||||
|
};
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
// Forward declaration of PinholeCameraCalX is defined here.
|
// Forward declaration of PinholeCameraCalX is defined here.
|
||||||
#include <gtsam/geometry/SimpleCamera.h>
|
#include <gtsam/geometry/SimpleCamera.h>
|
||||||
// Some typedefs for common camera types
|
// Some typedefs for common camera types
|
||||||
|
|
|
@ -163,25 +163,6 @@ class BearingS2 {
|
||||||
void serializable() const; // enabling serialization functionality
|
void serializable() const; // enabling serialization functionality
|
||||||
};
|
};
|
||||||
|
|
||||||
#include <gtsam_unstable/geometry/Similarity3.h>
|
|
||||||
class PointPairs
|
|
||||||
{
|
|
||||||
PointPairs();
|
|
||||||
size_t size() const;
|
|
||||||
bool empty() const;
|
|
||||||
gtsam::Point3Pair at(size_t n) const;
|
|
||||||
void push_back(const gtsam::Point3Pair& point_pair);
|
|
||||||
};
|
|
||||||
|
|
||||||
class Similarity3 {
|
|
||||||
Similarity3();
|
|
||||||
Similarity3(double s);
|
|
||||||
Similarity3(const gtsam::Rot3& R, const gtsam::Point3& t, double s);
|
|
||||||
Similarity3(const Matrix& R, const Vector& t, double s);
|
|
||||||
Similarity3(const Matrix& T);
|
|
||||||
|
|
||||||
static Similarity3 Align(const gtsam::PointPairs & abPointPairs);
|
|
||||||
};
|
|
||||||
|
|
||||||
#include <gtsam_unstable/geometry/SimWall2D.h>
|
#include <gtsam_unstable/geometry/SimWall2D.h>
|
||||||
class SimWall2D {
|
class SimWall2D {
|
||||||
|
|
Loading…
Reference in New Issue