diff --git a/python/gtsam_examples/VisualISAM2Example.py b/python/gtsam_examples/VisualISAM2Example.py index 29a8180ad..9dafa13e7 100644 --- a/python/gtsam_examples/VisualISAM2Example.py +++ b/python/gtsam_examples/VisualISAM2Example.py @@ -34,7 +34,7 @@ def visual_ISAM2_plot(poses, points, result): # Plot cameras i = 0 while result.exists(X(i)): - pose_i = result.pose3_at(X(i)) + pose_i = result.atPose3(X(i)) gtsam_utils.plotPose3(fignum, pose_i, 10) i += 1 @@ -114,10 +114,10 @@ def visual_ISAM2_example(): print("****************************************************") print("Frame", i, ":") for j in range(i + 1): - print(X(j), ":", currentEstimate.pose3_at(X(j))) + print(X(j), ":", currentEstimate.atPose3(X(j))) for j in range(len(points)): - print(L(j), ":", currentEstimate.point3_at(L(j))) + print(L(j), ":", currentEstimate.atPoint3(L(j))) visual_ISAM2_plot(poses, points, currentEstimate) diff --git a/python/handwritten/nonlinear/Values.cpp b/python/handwritten/nonlinear/Values.cpp index 83d33ca3c..84e82f376 100644 --- a/python/handwritten/nonlinear/Values.cpp +++ b/python/handwritten/nonlinear/Values.cpp @@ -31,57 +31,12 @@ using namespace boost::python; using namespace gtsam; -/** The function ValuesAt is a workaround to be able to call the correct templated version - * of Values::at. Without it, python would only try to match the last 'at' metho defined - * below. With this wrapper function we can call 'at' in python passing an extra type, - * which will define the type to be returned. Example: - * - * >>> import gtsam - * >>> v = gtsam.nonlinear.Values() - * >>> v.insert(1,gtsam.geometry.Point3()) - * >>> v.insert(2,gtsam.geometry.Rot3()) - * >>> v.insert(3,gtsam.geometry.Pose3()) - * >>> v.at(1,gtsam.geometry.Point3()) - * >>> v.at(2,gtsam.geometry.Rot3()) - * >>> v.at(3,gtsam.geometry.Pose3()) - * - * A more 'pythonic' way I think would be to not use this function and define different - * 'at' methods below using the name of the type in the function name, like: - * - * .def("point3_at", &Values::at, return_internal_reference<>()) - * .def("rot3_at", &Values::at, return_internal_reference<>()) - * .def("pose3_at", &Values::at, return_internal_reference<>()) - * - * and then they could be accessed from python as - * - * >>> import gtsam - * >>> v = gtsam.nonlinear.Values() - * >>> v.insert(1,gtsam.geometry.Point3()) - * >>> v.insert(2,gtsam.geometry.Rot3()) - * >>> v.insert(3,gtsam.geometry.Pose3()) - * >>> v.point3_at(1) - * >>> v.rot3_at(2) - * >>> v.pose3_at(3) - * - * In fact, I just saw the pythonic way sounds more clear, so I'm sticking with this and - * leaving the comments here for future reference. I'm using the PEP0008 for method naming. - * See: https://www.python.org/dev/peps/pep-0008/#function-and-method-arguments - */ -// template -// const T & ValuesAt( const Values & v, Key j, T /*type*/) -// { -// return v.at(j); -// } - BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS(print_overloads, Values::print, 0, 1); void exportValues(){ - // NOTE: Apparently the class 'Value'' is deprecated, so the commented lines below - // will compile, but are useless in the python wrapper. We need to use specific - // 'at' and 'insert' methods for each type. - // const Value& (Values::*at1)(Key) const = &Values::at; - // void (Values::*insert1)(Key, const Value&) = &Values::insert; + typedef imuBias::ConstantBias Bias; + bool (Values::*exists1)(Key) const = &Values::exists; void (Values::*insert_point2)(Key, const gtsam::Point2&) = &Values::insert; void (Values::*insert_rot2) (Key, const gtsam::Rot2&) = &Values::insert; @@ -89,10 +44,9 @@ void exportValues(){ void (Values::*insert_point3)(Key, const gtsam::Point3&) = &Values::insert; void (Values::*insert_rot3) (Key, const gtsam::Rot3&) = &Values::insert; void (Values::*insert_pose3) (Key, const gtsam::Pose3&) = &Values::insert; - void (Values::*insert_bias) (Key, const gtsam::imuBias::ConstantBias&) = &Values::insert; + void (Values::*insert_bias) (Key, const Bias&) = &Values::insert; void (Values::*insert_vector3) (Key, const gtsam::Vector3&) = &Values::insert; - class_("Values", init<>()) .def(init()) .def("clear", &Values::clear) @@ -104,9 +58,6 @@ void exportValues(){ .def("print", &Values::print, print_overloads(args("s"))) .def("size", &Values::size) .def("swap", &Values::swap) - // NOTE: Following commented lines add useless methods on Values - // .def("insert", insert1) - // .def("at", at1, return_value_policy()) .def("insert", insert_point2) .def("insert", insert_rot2) .def("insert", insert_pose2) @@ -115,14 +66,14 @@ void exportValues(){ .def("insert", insert_pose3) .def("insert", insert_bias) .def("insert", insert_vector3) - // NOTE: The following commented lines are another way of specializing the return type. - // See long comment above. - // .def("at", &ValuesAt, return_internal_reference<>()) - // .def("at", &ValuesAt, return_internal_reference<>()) - // .def("at", &ValuesAt, return_internal_reference<>()) - .def("point3_at", &Values::at, return_value_policy()) - .def("rot3_at", &Values::at, return_value_policy()) - .def("pose3_at", &Values::at, return_value_policy()) + .def("atPoint2", &Values::at, return_value_policy()) + .def("atRot2", &Values::at, return_value_policy()) + .def("atPose2", &Values::at, return_value_policy()) + .def("atPoint3", &Values::at, return_value_policy()) + .def("atRot3", &Values::at, return_value_policy()) + .def("atPose3", &Values::at, return_value_policy()) + .def("atConstantBias", &Values::at, return_value_policy()) + .def("atVector3", &Values::at, return_value_policy()) .def("exists", exists1) .def("keys", &Values::keys) ;