From 414e6b58f91027e4050457e65ee1fbf30fab58a6 Mon Sep 17 00:00:00 2001 From: Andrew Melim Date: Wed, 20 Nov 2013 02:30:44 +0000 Subject: [PATCH] Finally fixed templates, moved into single library for simplicity, add noisemodels, nonlinear --- python/CMakeLists.txt | 6 +- python/exportgtsam.cpp | 63 +++++++++++++++++++ python/geometry/exportGeometry.cpp | 13 ---- python/linear/NoiseModel.cpp | 13 ++++ .../nonlinear/LevenbergMarquardtOptimizer.cpp | 12 ++++ python/nonlinear/NonlinearFactorGraph.cpp | 18 ++++++ python/nonlinear/Values.cpp | 19 ++++++ python/slam/BearingFactor.cpp | 2 +- python/slam/BetweenFactor.cpp | 2 +- python/slam/PriorFactor.cpp | 8 +-- python/slam/exportSlam.cpp | 24 ------- 11 files changed, 135 insertions(+), 45 deletions(-) create mode 100644 python/exportgtsam.cpp delete mode 100644 python/geometry/exportGeometry.cpp create mode 100644 python/linear/NoiseModel.cpp create mode 100644 python/nonlinear/LevenbergMarquardtOptimizer.cpp create mode 100644 python/nonlinear/NonlinearFactorGraph.cpp create mode 100644 python/nonlinear/Values.cpp delete mode 100644 python/slam/exportSlam.cpp diff --git a/python/CMakeLists.txt b/python/CMakeLists.txt index e503bdb45..cd9861dc0 100644 --- a/python/CMakeLists.txt +++ b/python/CMakeLists.txt @@ -18,8 +18,10 @@ file(GLOB slam_src "slam/*.cpp") file(GLOB symbolic_src "symbolic/*.cpp") #wrap_python("base" ${PROJECT_SOURCE_DIR}/python/${PROJECT_NAME} ${base_src}) -wrap_python("geometry" ${PROJECT_SOURCE_DIR}/python/gtsam ${geometry_src}) -wrap_python("slam" ${PROJECT_SOURCE_DIR}/python/gtsam ${slam_src}) +wrap_python("gtsam" ${PROJECT_SOURCE_DIR}/python/gtsam exportgtsam.cpp + ${geometry_src} ${linear_src} ${nonlinear_src} ${slam_src}) +#wrap_python("nonlinear" ${PROJECT_SOURCE_DIR}/python/gtsam ${nonlinear_src}) +#wrap_python("slam" ${PROJECT_SOURCE_DIR}/python/gtsam ${slam_src}) #add_python_export_library(${PROJECT_NAME}_test ${PROJECT_SOURCE_DIR}/python/${PROJECT_NAME} # ${AUTOGEN_TEST_FILES} #) \ No newline at end of file diff --git a/python/exportgtsam.cpp b/python/exportgtsam.cpp new file mode 100644 index 000000000..51e0ae1f3 --- /dev/null +++ b/python/exportgtsam.cpp @@ -0,0 +1,63 @@ +#include +#include + +#include +#include +#include +#include +#include + +using namespace boost::python; +using namespace gtsam; +using namespace std; + +// Geometery +void exportPoint2(); +void exportRot2(); +void exportPose2(); + +// Linear +void exportNoiseModels(); + +// Nonlinear +void exportValues(); +void exportNonlinearFactorGraph(); +void exportLevenbergMarquardtOptimizer(); + +// Slam +template< class FACTOR, class VALUE > +void exportPriorFactor(const std::string& name){ + class_< FACTOR >(name.c_str(), init<>()) + .def(init< Key, VALUE&, SharedNoiseModel >()) + ; +} + +template +void exportBetweenFactor(const std::string& name){ + class_(name.c_str(), init<>()) + .def(init()) + ; +} + +typedef gtsam::PriorFactor Point2PriorFactor; +typedef gtsam::PriorFactor Pose2PriorFactor; +typedef gtsam::BetweenFactor Pose2BetweenFactor; + +//-----------------------------------// + +BOOST_PYTHON_MODULE(libgtsam){ + using namespace boost::python; + exportPoint2(); + exportRot2(); + exportPose2(); + + exportNoiseModels(); + + exportValues(); + exportNonlinearFactorGraph(); + exportLevenbergMarquardtOptimizer(); + + exportPriorFactor< Point2PriorFactor, Point2 >("Point2PriorFactor"); + exportPriorFactor< Pose2PriorFactor, Pose2 >("Pose2PriorFactor"); + exportBetweenFactor< Pose2BetweenFactor, Pose2 >("Pose2BetweenFactor"); +} \ No newline at end of file diff --git a/python/geometry/exportGeometry.cpp b/python/geometry/exportGeometry.cpp deleted file mode 100644 index 3887f7ca1..000000000 --- a/python/geometry/exportGeometry.cpp +++ /dev/null @@ -1,13 +0,0 @@ -#include -#include - -void exportPoint2(); -void exportRot2(); -void exportPose2(); - -BOOST_PYTHON_MODULE(libgeometry){ - using namespace boost::python; - exportPoint2(); - exportRot2(); - exportPose2(); -} \ No newline at end of file diff --git a/python/linear/NoiseModel.cpp b/python/linear/NoiseModel.cpp new file mode 100644 index 000000000..89ee26e9a --- /dev/null +++ b/python/linear/NoiseModel.cpp @@ -0,0 +1,13 @@ +#include +#include + +using namespace boost::python; +using namespace gtsam; + +void exportNoiseModels(){ + // Diagonal Noise Model, no constructor + class_("DiagonalNoiseModel", no_init) + .def("Sigmas", &noiseModel::Diagonal::Sigmas) + .staticmethod("Sigmas") + ; +} \ No newline at end of file diff --git a/python/nonlinear/LevenbergMarquardtOptimizer.cpp b/python/nonlinear/LevenbergMarquardtOptimizer.cpp new file mode 100644 index 000000000..b7e38359f --- /dev/null +++ b/python/nonlinear/LevenbergMarquardtOptimizer.cpp @@ -0,0 +1,12 @@ +#include +#include + +using namespace boost::python; +using namespace gtsam; + +void exportLevenbergMarquardtOptimizer(){ + class_("LevenbergMarquardtOptimizer", + init()) + .def("optimize", &LevenbergMarquardtOptimizer::optimize, return_value_policy()) + ; +} \ No newline at end of file diff --git a/python/nonlinear/NonlinearFactorGraph.cpp b/python/nonlinear/NonlinearFactorGraph.cpp new file mode 100644 index 000000000..16aa4c6e4 --- /dev/null +++ b/python/nonlinear/NonlinearFactorGraph.cpp @@ -0,0 +1,18 @@ +#include +#include "gtsam/nonlinear/NonlinearFactorGraph.h" +#include + +using namespace boost::python; +using namespace gtsam; + + +void exportNonlinearFactorGraph(){ + + typedef boost::shared_ptr shared_factor; + + void (NonlinearFactorGraph::*push_back1)(const shared_factor& factor) = &NonlinearFactorGraph::push_back; + + class_("NonlinearFactorGraph", init<>()) + .def("push_back", push_back1) + ; +} \ No newline at end of file diff --git a/python/nonlinear/Values.cpp b/python/nonlinear/Values.cpp new file mode 100644 index 000000000..c1451cef1 --- /dev/null +++ b/python/nonlinear/Values.cpp @@ -0,0 +1,19 @@ +#include +#include + +using namespace boost::python; +using namespace gtsam; + +void exportValues(){ + + const Value& (Values::*at1)(Key) const = &Values::at; + bool (Values::*exists1)(Key) const = &Values::exists; + void (Values::*insert1)(Key, const Value&) = &Values::insert; + + class_("Values", init<>()) + .def(init()) + .def("at", at1, return_value_policy()) + .def("exists", exists1) + .def("insert", insert1, return_value_policy()) + ; +} \ No newline at end of file diff --git a/python/slam/BearingFactor.cpp b/python/slam/BearingFactor.cpp index 63d4bb3ed..b13d1f281 100644 --- a/python/slam/BearingFactor.cpp +++ b/python/slam/BearingFactor.cpp @@ -7,7 +7,7 @@ using namespace gtsam; using namespace std; template -void exposeBearingFactor(const std::string& name){ +void exportBearingFactor(const std::string& name){ class_(name, init<>()) ; } \ No newline at end of file diff --git a/python/slam/BetweenFactor.cpp b/python/slam/BetweenFactor.cpp index 3674614da..2732e4e7e 100644 --- a/python/slam/BetweenFactor.cpp +++ b/python/slam/BetweenFactor.cpp @@ -7,7 +7,7 @@ using namespace gtsam; using namespace std; template -void exposeBetweenFactor(const std::string& name){ +void exportBetweenFactor(const std::string& name){ class_(name, init<>()) .def(init()) ; diff --git a/python/slam/PriorFactor.cpp b/python/slam/PriorFactor.cpp index e1ee27602..1984fe144 100644 --- a/python/slam/PriorFactor.cpp +++ b/python/slam/PriorFactor.cpp @@ -6,9 +6,9 @@ using namespace gtsam; using namespace std; -template -void exposePriorFactor(const std::string& name){ - class_(name, init<>()) - .def(init()) +template< class FACTOR, class VALUE > +void exportPriorFactor(const std::string& name){ + class_< FACTOR >(name.c_str(), init<>()) + .def(init< Key, VALUE&, SharedNoiseModel >()) ; } \ No newline at end of file diff --git a/python/slam/exportSlam.cpp b/python/slam/exportSlam.cpp deleted file mode 100644 index fdd1d1549..000000000 --- a/python/slam/exportSlam.cpp +++ /dev/null @@ -1,24 +0,0 @@ -#include -#include - -#include -#include -#include -#include - -template void exportPriorFactor(const std::string& name); -template void exportBetweenFactor(const std::string& name); - -BOOST_PYTHON_MODULE(libgeometry){ - using namespace boost::python; - - typedef gtsam::PriorFactor Point2PriorFactor; - typedef gtsam::PriorFactor Pose2PriorFactor; - - exportPriorFactor("Point2PriorFactor"); - exportPriorFactor("Pose2PriorFactor"); - - typedef gtsam::BetweenFactor Pose2BetweenFactor; - - exportBetweenFactor("Pose2BetweenFactor"); -} \ No newline at end of file