wrap Pose2Pairs
parent
19335972ed
commit
c716f63219
|
@ -23,8 +23,8 @@ PYBIND11_MAKE_OPAQUE(
|
|||
std::vector<gtsam::Point2, Eigen::aligned_allocator<gtsam::Point2>>);
|
||||
PYBIND11_MAKE_OPAQUE(gtsam::Point2Pairs);
|
||||
PYBIND11_MAKE_OPAQUE(gtsam::Point3Pairs);
|
||||
PYBIND11_MAKE_OPAQUE(gtsam::Pose2Pairs);
|
||||
PYBIND11_MAKE_OPAQUE(gtsam::Pose3Pairs);
|
||||
PYBIND11_MAKE_OPAQUE(std::vector<gtsam::Pose3>);
|
||||
PYBIND11_MAKE_OPAQUE(
|
||||
gtsam::CameraSet<gtsam::PinholeCamera<gtsam::Cal3Bundler>>);
|
||||
PYBIND11_MAKE_OPAQUE(gtsam::CameraSet<gtsam::PinholeCamera<gtsam::Cal3Bundler>>);
|
||||
PYBIND11_MAKE_OPAQUE(gtsam::CameraSet<gtsam::PinholeCamera<gtsam::Cal3_S2>>);
|
||||
|
|
|
@ -16,6 +16,7 @@ py::bind_vector<
|
|||
m_, "Point2Vector");
|
||||
py::bind_vector<std::vector<gtsam::Point2Pair>>(m_, "Point2Pairs");
|
||||
py::bind_vector<std::vector<gtsam::Point3Pair>>(m_, "Point3Pairs");
|
||||
py::bind_vector<std::vector<gtsam::Pose2Pair>>(m_, "Pose2Pairs");
|
||||
py::bind_vector<std::vector<gtsam::Pose3Pair>>(m_, "Pose3Pairs");
|
||||
py::bind_vector<std::vector<gtsam::Pose3>>(m_, "Pose3Vector");
|
||||
py::bind_vector<gtsam::CameraSet<gtsam::PinholeCamera<gtsam::Cal3_S2>>>(
|
||||
|
|
Loading…
Reference in New Issue