Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Wrap FindKarcherMean for Rot3 #1069

Merged
merged 16 commits into from
Jan 28, 2022
Merged
14 changes: 13 additions & 1 deletion gtsam/slam/slam.i
Original file line number Diff line number Diff line change
Expand Up @@ -316,13 +316,25 @@ class InitializePose3 {
static gtsam::Values initialize(const gtsam::NonlinearFactorGraph& graph);
};

#include <gtsam/slam/KarcherMeanFactor-inl.h>
#include <gtsam/slam/KarcherMeanFactor.h>
template <T = {gtsam::Point2, gtsam::Rot2, gtsam::Pose2, gtsam::Point3,
gtsam::SO3, gtsam::SO4, gtsam::Rot3, gtsam::Pose3}>
virtual class KarcherMeanFactor : gtsam::NonlinearFactor {
KarcherMeanFactor(const gtsam::KeyVector& keys);
};

class Rot3Vector {
Rot3Vector();
size_t size() const;

// structure specific methods
gtsam::Rot3 at(size_t i) const;
void push_back(const gtsam::Rot3& R);
johnwlambert marked this conversation as resolved.
Show resolved Hide resolved
};
gtsam::Rot3 FindKarcherMean<gtsam::Rot3>(const Rot3Vector &rotations);
typedef FindKarcherMean<gtsam::Rot3> FindKarcherMeanRot3;
gtsam::Rot3 FindKarcherMeanRot3(const gtsam::Rot3Vector& rotations);

#include <gtsam/slam/FrobeniusFactor.h>
gtsam::noiseModel::Isotropic* ConvertNoiseModel(gtsam::noiseModel::Base* model,
size_t d);
Expand Down
1 change: 1 addition & 0 deletions python/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -45,6 +45,7 @@ set(ignore
gtsam::Point3Pairs
gtsam::Pose3Pairs
gtsam::Pose3Vector
gtsam::Rot3Vector
gtsam::KeyVector
gtsam::BinaryMeasurementsUnit3
gtsam::DiscreteKey
Expand Down
1 change: 1 addition & 0 deletions python/gtsam/preamble/slam.h
Original file line number Diff line number Diff line change
Expand Up @@ -15,3 +15,4 @@ PYBIND11_MAKE_OPAQUE(
std::vector<boost::shared_ptr<gtsam::BetweenFactor<gtsam::Pose3> > >);
PYBIND11_MAKE_OPAQUE(
std::vector<boost::shared_ptr<gtsam::BetweenFactor<gtsam::Pose2> > >);
PYBIND11_MAKE_OPAQUE(std::vector<gtsam::Rot3, Eigen::aligned_allocator<gtsam::Rot3> >);
1 change: 1 addition & 0 deletions python/gtsam/specializations/slam.h
Original file line number Diff line number Diff line change
Expand Up @@ -17,3 +17,4 @@ py::bind_vector<
py::bind_vector<
std::vector<boost::shared_ptr<gtsam::BetweenFactor<gtsam::Pose2> > > >(
m_, "BetweenFactorPose2s");
py::bind_vector<std::vector<gtsam::Rot3, Eigen::aligned_allocator<gtsam::Rot3>>(m_, "Rot3Vector");
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

there is a missing ">" at the end here, that should let you wrap Rot3Vector at least.