add sim3 Point3 align to wrapper

release/4.3a0
John Lambert 2021-02-24 15:26:13 -05:00
parent 8552752839
commit 0effe69df2
4 changed files with 14 additions and 1 deletions

View File

@ -24,7 +24,7 @@
namespace gtsam {
using std::vector;
using PointPairs = vector<Point3Pair>;
typedef PointPairs = vector<Point3Pair>;
namespace {
/// Subtract centroids from point pairs.

View File

@ -164,12 +164,23 @@ class BearingS2 {
};
#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>

View File

@ -41,6 +41,7 @@ set(ignore
gtsam::BetweenFactorPose2s
gtsam::BetweenFactorPose3s
gtsam::Point2Vector
gtsam::PointPairs
gtsam::Pose3Vector
gtsam::KeyVector
gtsam::BinaryMeasurementsUnit3

View File

@ -6,6 +6,7 @@ py::bind_vector<std::vector<gtsam::Key, tbb::tbb_allocator<gtsam::Key> > >(m_, "
py::bind_vector<std::vector<gtsam::Key> >(m_, "KeyVector");
#endif
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::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::Pose2> > > >(m_, "BetweenFactorPose2s");