Rename PointPairs to Point3Pairs everywhere per popular demand
parent
7604633c43
commit
104031dca3
|
|
@ -1070,9 +1070,9 @@ class PinholeCamera {
|
||||||
|
|
||||||
|
|
||||||
#include <gtsam/geometry/Similarity3.h>
|
#include <gtsam/geometry/Similarity3.h>
|
||||||
class PointPairs
|
class Point3Pairs
|
||||||
{
|
{
|
||||||
PointPairs();
|
Point3Pairs();
|
||||||
size_t size() const;
|
size_t size() const;
|
||||||
bool empty() const;
|
bool empty() const;
|
||||||
gtsam::Point3Pair at(size_t n) const;
|
gtsam::Point3Pair at(size_t n) const;
|
||||||
|
|
@ -1088,7 +1088,7 @@ class Similarity3 {
|
||||||
Similarity3(const Matrix& T);
|
Similarity3(const Matrix& T);
|
||||||
|
|
||||||
gtsam::Pose3 transformFrom(const gtsam::Pose3& T);
|
gtsam::Pose3 transformFrom(const gtsam::Pose3& T);
|
||||||
static Similarity3 Align(const gtsam::PointPairs & abPointPairs);
|
static Similarity3 Align(const gtsam::Point3Pairs & abPointPairs);
|
||||||
static Similarity3 Align(const gtsam::Pose3Pairs & abPosePairs);
|
static Similarity3 Align(const gtsam::Pose3Pairs & abPosePairs);
|
||||||
|
|
||||||
// Standard Interface
|
// Standard Interface
|
||||||
|
|
|
||||||
|
|
@ -41,7 +41,7 @@ set(ignore
|
||||||
gtsam::BetweenFactorPose2s
|
gtsam::BetweenFactorPose2s
|
||||||
gtsam::BetweenFactorPose3s
|
gtsam::BetweenFactorPose3s
|
||||||
gtsam::Point2Vector
|
gtsam::Point2Vector
|
||||||
gtsam::PointPairs
|
gtsam::Point3Pairs
|
||||||
gtsam::Pose3Pairs
|
gtsam::Pose3Pairs
|
||||||
gtsam::Pose3Vector
|
gtsam::Pose3Vector
|
||||||
gtsam::KeyVector
|
gtsam::KeyVector
|
||||||
|
|
|
||||||
|
|
@ -6,7 +6,7 @@ py::bind_vector<std::vector<gtsam::Key, tbb::tbb_allocator<gtsam::Key> > >(m_, "
|
||||||
py::bind_vector<std::vector<gtsam::Key> >(m_, "KeyVector");
|
py::bind_vector<std::vector<gtsam::Key> >(m_, "KeyVector");
|
||||||
#endif
|
#endif
|
||||||
py::bind_vector<std::vector<gtsam::Point2, Eigen::aligned_allocator<gtsam::Point2> > >(m_, "Point2Vector");
|
py::bind_vector<std::vector<gtsam::Point2, Eigen::aligned_allocator<gtsam::Point2> > >(m_, "Point2Vector");
|
||||||
py::bind_vector<std::vector<gtsam::Point3Pair> >(m_, "PointPairs");
|
py::bind_vector<std::vector<gtsam::Point3Pair> >(m_, "Point3Pairs");
|
||||||
py::bind_vector<std::vector<gtsam::Pose3Pair> >(m_, "Pose3Pairs");
|
py::bind_vector<std::vector<gtsam::Pose3Pair> >(m_, "Pose3Pairs");
|
||||||
py::bind_vector<std::vector<gtsam::Pose3> >(m_, "Pose3Vector");
|
py::bind_vector<std::vector<gtsam::Pose3> >(m_, "Pose3Vector");
|
||||||
py::bind_vector<std::vector<boost::shared_ptr<gtsam::BetweenFactor<gtsam::Pose3> > > >(m_, "BetweenFactorPose3s");
|
py::bind_vector<std::vector<boost::shared_ptr<gtsam::BetweenFactor<gtsam::Pose3> > > >(m_, "BetweenFactorPose3s");
|
||||||
|
|
|
||||||
Loading…
Reference in New Issue