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

Wrap FindKarcherMean for Rot3 #1069

merged 16 commits into from
Jan 28, 2022

Conversation

johnwlambert
Copy link
Contributor

@johnwlambert johnwlambert commented Jan 26, 2022

Wrap gtsam.FindKarcherMean with Rot3Vector argument (a new type defined in Rot3.h)

Previously, only KarcherMeanFactor was wrapped, meaning additional boilerplate (create a factor graph, create an optimizer, and optimize it) was required to compute the Karcher Mean.

Rot3Vector is a new type that is essentially a vector of Rot3 objects, although an Eigen aligned allocator is needed.

@@ -323,6 +323,9 @@ virtual class KarcherMeanFactor : gtsam::NonlinearFactor {
KarcherMeanFactor(const gtsam::KeyVector& keys);
};

template <T = {gtsam::Rot3}>
const T FindKarcherMean<T>(const std::vector<T>& rotations);
Copy link
Contributor Author

Choose a reason for hiding this comment

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

@varunagrawal @ProfFan question for you all -- do we have support for std::vector yet? or do we need to make a new type alias here such as Rot3Vector?

Copy link
Collaborator

Choose a reason for hiding this comment

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

No because of MATLAB end

Copy link
Member

Choose a reason for hiding this comment

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

huh? I thought that std::vector worked with wrapper??

gtsam/slam/slam.i Outdated Show resolved Hide resolved
gtsam::Rot3 at(size_t i) const;
void push_back(const gtsam::Rot3& R);
};
const gtsam::Rot3 FindKarcherMean<gtsam::Rot3>(const Rot3Vector& rotations);
Copy link
Contributor

Choose a reason for hiding this comment

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

no need for const in the return type: gtsam::Rot3 FindKarcherMean<gtsam::Rot3>(const Rot3Vector& rotations);

@@ -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>>(m_, "Rot3Vector");
Copy link
Collaborator

Choose a reason for hiding this comment

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

Are you sure you don't need aligned allocator?

Copy link
Contributor Author

Choose a reason for hiding this comment

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

Thanks for the review @ProfFan and @akshay-krishnan.

Let me check about aligned allocator. Btw I don't love the name Rot3Vector so much ... sounds like a vector representation of a Rot3. But Rot3Set would not be consistent with Pose3Vector nomenclature. So I guess it works.

Copy link
Collaborator

@ProfFan ProfFan left a comment

Choose a reason for hiding this comment

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

LGTM minus one

void push_back(const gtsam::Rot3& R);
};
typedef FindKarcherMean<gtsam::Rot3> FindKarcherMeanRot3;
gtsam::Rot3 FindKarcherMeanRot3(const Rot3Vector& rotations);
Copy link
Contributor Author

Choose a reason for hiding this comment

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

@dellaert @ProfFan the CI states: Cannot find class FindKarcherMean in module!. Strange. Should we be including #include <gtsam/slam/KarcherMeanFactor.h> instead of #include <gtsam/slam/KarcherMeanFactor-inl.h> in this .i file?

Traceback (most recent call last):
  File "/home/runner/work/gtsam/gtsam/wrap/scripts/pybind_wrap.py", line 94, in <module>
    main()
  File "/home/runner/work/gtsam/gtsam/wrap/scripts/pybind_wrap.py", line 85, in main
    wrapper.wrap_submodule(args.src)
  File "/home/runner/work/gtsam/gtsam/wrap/gtwrap/pybind_wrapper.py", line 696, in wrap_submodule
    cc_content = self.wrap_file(content, module_name=module_name)
  File "/home/runner/work/gtsam/gtsam/wrap/gtwrap/pybind_wrapper.py", line 626, in wrap_file
    module = instantiator.instantiate_namespace(module)
  File "/home/runner/work/gtsam/gtsam/wrap/gtwrap/template_instantiator/namespace.py", line 80, in instantiate_namespace
    element = instantiate_namespace(element)
  File "/home/runner/work/gtsam/gtsam/wrap/gtwrap/template_instantiator/namespace.py", line 59, in instantiate_namespace
    typedef_inst.typename)
  File "/home/runner/work/gtsam/gtsam/wrap/gtwrap/interface_parser/namespace.py", line 109, in find_class_or_function
    typename.name))
ValueError: Cannot find class FindKarcherMean in module!
make[2]: *** [python/slam.cpp] Error 1
python/CMakeFiles/pybind_wrap_gtsam.dir/build.make:164: recipe for target 'python/slam.cpp' failed
CMakeFiles/Makefile2:6769: recipe for target 'python/CMakeFiles/pybind_wrap_gtsam.dir/all' failed
make[1]: *** [python/CMakeFiles/pybind_wrap_gtsam.dir/all] Error 2
make[1]: *** Waiting for unfinished jobs....

Copy link
Collaborator

Choose a reason for hiding this comment

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

Should be the simple .h file. Is the FindKarcherMean class defined in the .i file?

Copy link
Contributor Author

Choose a reason for hiding this comment

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

FindKarcherMean is not defined in the .i file yet. I should add that, no that I think about it... (btw it is a function, not a class)

For some reason the inl.h file is being included, instead of the .h file currently. Not sure why though

Copy link
Contributor Author

@johnwlambert johnwlambert Jan 27, 2022

Choose a reason for hiding this comment

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

Actually, since we can use std:: in .i, then we can't define FindKarcherMean in the .i file, since it relies on std::

template <class T>
T FindKarcherMean(const std::vector<T, Eigen::aligned_allocator<T>> &rotations);

template <class T> T FindKarcherMean(std::initializer_list<T> &&rotations);

So I guess the typedef for FindKarcherMeanRot3 needs to go into the .h file directly?

Copy link
Member

Choose a reason for hiding this comment

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

But you can use std::. Who is telling you you can't ?

Copy link
Collaborator

Choose a reason for hiding this comment

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

Matlab wrapper needs correct signature, unless @varunagrawal implemented something that handles this?

Copy link
Collaborator

Choose a reason for hiding this comment

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

If I'm not mistaken, std should be useable. When in doubt, check out or write a test for it in the wrap project. :)

(I spent a whole month writing those tests folks, please make them worth my time 😅)

Copy link
Member

Choose a reason for hiding this comment

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

Matlab wrapper needs correct signature, unless @varunagrawal implemented something that handles this?

I don't know what that means. Example?

template <class T>
T FindKarcherMean(const std::vector<T, Eigen::aligned_allocator<T>> &rotations);

template <class T> T FindKarcherMean(std::initializer_list<T> &&rotations);
Copy link
Member

Choose a reason for hiding this comment

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

Not sure what this would translate to in python.....

@dellaert
Copy link
Member

@johnwlambert , are you planning on still submitting other commits? You should know that on every push the CI runs 34 checks. It is recommended you do everything locally, including make check and make python-install, and then push once you think everything was addressed.

@dellaert
Copy link
Member

If you are planning another push, kindly cancel the CI jobs for this PR.

@johnwlambert
Copy link
Contributor Author

If you are planning another push, kindly cancel the CI jobs for this PR.

I've gotten to like the Github.com interface a bit too much : - ) I've cancelled the nonrelevant CI jobs, thanks.

@dellaert
Copy link
Member

Yeah, please don't develop with our CI as your compute :-) It clogs all other PRs, and I'm trying to build a wheel (which will unfortunately not include this PR).

@@ -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.

@akshay-krishnan
Copy link
Contributor

It looks like we cannot use std::initializer_list or Eigen::aligned_allocator in slam.i.
So the only way I can think of is to have a typedef for std::vector<Rot3, Eigen::aligned_allocator> and define another function specifically for Rot3 (using the typedef as the argument).
This seems a little hacky.
Alternatively, we could just re-implement FindKarcherMean in python using the KarcherMeanFactor which has been wrapped. Its a really small function. @johnwlambert WDYT?

@johnwlambert
Copy link
Contributor Author

Thanks for taking a look @akshay-krishnan. Yeah this seems like we should just use KarcherMeanFactor directly in Python w/ an optimizer of our choice.

@dellaert
Copy link
Member

Nonono! Let's fix this. Let me take a quick look.

@dellaert dellaert reopened this Jan 28, 2022
@dellaert
Copy link
Member

Why, @johnwlambert , there is not even a unit test here I can start from :-)

@dellaert
Copy link
Member

@johnwlambert what were you actually trying to accomplish with this PR? There is no PR comment. And, there is test_KarcherMeanFactor.py that just works, I think?

@johnwlambert
Copy link
Contributor Author

Thanks Frank. Yeah we were just trying to avoid repeating that boilerplate from https://github.com/borglab/gtsam/blob/develop/python/gtsam/tests/test_KarcherMeanFactor.py#L24. But we can use it in Python, no problem. A simple unit test would look like

import gtsam
from gtsam import Rot3, Rot3Vector
from gtsam.utils.test_case import GtsamTestCase


class TestKarcherMean(GtsamTestCase):
    """Tests for DecisionTreeFactors."""

    def test_find_karcher_mean_identity() -> None:
        """Averaging 3 identity rotations should yield the identity."""
        a1Rb1 = Rot3()
        a2Rb2 = Rot3()
        a3Rb3 = Rot3()

        aRb_list = Rot3Vector([a1Rb1, a2Rb2, a3Rb3])
        aRb_expected = Rot3()

        aRb = gtsam.FindKarcherMeanRot3(aRb_list)
        self.assertTrue(aRb.equals(aRb_expected))

but there are already some implemented here, which seem fine.

@dellaert
Copy link
Member

@johnwlambert I think I fixed it, could you please update the PR with a good description after looking at the file differences?

@dellaert dellaert merged commit 3ba6566 into develop Jan 28, 2022
@dellaert dellaert deleted the wrap-karcher-mean-rot3 branch January 28, 2022 20:41
@johnwlambert
Copy link
Contributor Author

@johnwlambert I think I fixed it, could you please update the PR with a good description after looking at the file differences?

Beautiful work Frank. I added a bit to the description you wrote. Thanks!

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

Successfully merging this pull request may close these issues.

5 participants