From 13c164f25d4683bd1720b564ee3dcbf67b4ffff5 Mon Sep 17 00:00:00 2001 From: John Lambert Date: Mon, 30 Aug 2021 16:38:47 -0400 Subject: [PATCH] add Pose2.align() to wrapper --- gtsam/geometry/geometry.i | 10 ++++++++++ 1 file changed, 10 insertions(+) diff --git a/gtsam/geometry/geometry.i b/gtsam/geometry/geometry.i index 0e303cbcd..c495c22d9 100644 --- a/gtsam/geometry/geometry.i +++ b/gtsam/geometry/geometry.i @@ -31,6 +31,14 @@ class Point2 { // enable pickling in python void pickle() const; }; + +class Point2Pairs { + Point2Pairs(); + size_t size() const; + bool empty() const; + gtsam::Point2Pair at(size_t n) const; + void push_back(const gtsam::Point2Pair& point_pair); +}; // std::vector class Point2Vector { @@ -428,6 +436,8 @@ class Pose2 { // enable pickling in python void pickle() const; + + gtsam::Pose2 align(const gtsam::Point2Pairs& pairs); }; #include