Finally fixed templates, moved into single library for simplicity, add noisemodels, nonlinear
parent
d0efbadac8
commit
414e6b58f9
|
@ -18,8 +18,10 @@ file(GLOB slam_src "slam/*.cpp")
|
||||||
file(GLOB symbolic_src "symbolic/*.cpp")
|
file(GLOB symbolic_src "symbolic/*.cpp")
|
||||||
|
|
||||||
#wrap_python("base" ${PROJECT_SOURCE_DIR}/python/${PROJECT_NAME} ${base_src})
|
#wrap_python("base" ${PROJECT_SOURCE_DIR}/python/${PROJECT_NAME} ${base_src})
|
||||||
wrap_python("geometry" ${PROJECT_SOURCE_DIR}/python/gtsam ${geometry_src})
|
wrap_python("gtsam" ${PROJECT_SOURCE_DIR}/python/gtsam exportgtsam.cpp
|
||||||
wrap_python("slam" ${PROJECT_SOURCE_DIR}/python/gtsam ${slam_src})
|
${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}
|
#add_python_export_library(${PROJECT_NAME}_test ${PROJECT_SOURCE_DIR}/python/${PROJECT_NAME}
|
||||||
# ${AUTOGEN_TEST_FILES}
|
# ${AUTOGEN_TEST_FILES}
|
||||||
#)
|
#)
|
|
@ -0,0 +1,63 @@
|
||||||
|
#include <boost/python.hpp>
|
||||||
|
#include <boost/cstdint.hpp>
|
||||||
|
|
||||||
|
#include <gtsam/geometry/Pose2.h>
|
||||||
|
#include <gtsam/nonlinear/Values.h>
|
||||||
|
#include <gtsam/nonlinear/NonlinearFactorGraph.h>
|
||||||
|
#include <gtsam/slam/PriorFactor.h>
|
||||||
|
#include <gtsam/slam/BetweenFactor.h>
|
||||||
|
|
||||||
|
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<class FACTOR, class VALUE>
|
||||||
|
void exportBetweenFactor(const std::string& name){
|
||||||
|
class_<FACTOR>(name.c_str(), init<>())
|
||||||
|
.def(init<Key, Key, VALUE&, SharedNoiseModel>())
|
||||||
|
;
|
||||||
|
}
|
||||||
|
|
||||||
|
typedef gtsam::PriorFactor<gtsam::Point2> Point2PriorFactor;
|
||||||
|
typedef gtsam::PriorFactor<gtsam::Pose2> Pose2PriorFactor;
|
||||||
|
typedef gtsam::BetweenFactor<gtsam::Pose2> 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");
|
||||||
|
}
|
|
@ -1,13 +0,0 @@
|
||||||
#include <boost/python.hpp>
|
|
||||||
#include <boost/cstdint.hpp>
|
|
||||||
|
|
||||||
void exportPoint2();
|
|
||||||
void exportRot2();
|
|
||||||
void exportPose2();
|
|
||||||
|
|
||||||
BOOST_PYTHON_MODULE(libgeometry){
|
|
||||||
using namespace boost::python;
|
|
||||||
exportPoint2();
|
|
||||||
exportRot2();
|
|
||||||
exportPose2();
|
|
||||||
}
|
|
|
@ -0,0 +1,13 @@
|
||||||
|
#include <boost/python.hpp>
|
||||||
|
#include <gtsam/linear/NoiseModel.h>
|
||||||
|
|
||||||
|
using namespace boost::python;
|
||||||
|
using namespace gtsam;
|
||||||
|
|
||||||
|
void exportNoiseModels(){
|
||||||
|
// Diagonal Noise Model, no constructor
|
||||||
|
class_<noiseModel::Diagonal>("DiagonalNoiseModel", no_init)
|
||||||
|
.def("Sigmas", &noiseModel::Diagonal::Sigmas)
|
||||||
|
.staticmethod("Sigmas")
|
||||||
|
;
|
||||||
|
}
|
|
@ -0,0 +1,12 @@
|
||||||
|
#include <boost/python.hpp>
|
||||||
|
#include <gtsam/nonlinear/LevenbergMarquardtOptimizer.h>
|
||||||
|
|
||||||
|
using namespace boost::python;
|
||||||
|
using namespace gtsam;
|
||||||
|
|
||||||
|
void exportLevenbergMarquardtOptimizer(){
|
||||||
|
class_<LevenbergMarquardtOptimizer>("LevenbergMarquardtOptimizer",
|
||||||
|
init<const NonlinearFactorGraph&, const Values&, const LevenbergMarquardtParams&>())
|
||||||
|
.def("optimize", &LevenbergMarquardtOptimizer::optimize, return_value_policy<copy_const_reference>())
|
||||||
|
;
|
||||||
|
}
|
|
@ -0,0 +1,18 @@
|
||||||
|
#include <boost/python.hpp>
|
||||||
|
#include "gtsam/nonlinear/NonlinearFactorGraph.h"
|
||||||
|
#include <gtsam/nonlinear/NonlinearFactor.h>
|
||||||
|
|
||||||
|
using namespace boost::python;
|
||||||
|
using namespace gtsam;
|
||||||
|
|
||||||
|
|
||||||
|
void exportNonlinearFactorGraph(){
|
||||||
|
|
||||||
|
typedef boost::shared_ptr<NonlinearFactor> shared_factor;
|
||||||
|
|
||||||
|
void (NonlinearFactorGraph::*push_back1)(const shared_factor& factor) = &NonlinearFactorGraph::push_back;
|
||||||
|
|
||||||
|
class_<NonlinearFactorGraph>("NonlinearFactorGraph", init<>())
|
||||||
|
.def("push_back", push_back1)
|
||||||
|
;
|
||||||
|
}
|
|
@ -0,0 +1,19 @@
|
||||||
|
#include <boost/python.hpp>
|
||||||
|
#include <gtsam/nonlinear/Values.h>
|
||||||
|
|
||||||
|
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>("Values", init<>())
|
||||||
|
.def(init<Values>())
|
||||||
|
.def("at", at1, return_value_policy<copy_const_reference>())
|
||||||
|
.def("exists", exists1)
|
||||||
|
.def("insert", insert1, return_value_policy<copy_const_reference>())
|
||||||
|
;
|
||||||
|
}
|
|
@ -7,7 +7,7 @@ using namespace gtsam;
|
||||||
using namespace std;
|
using namespace std;
|
||||||
|
|
||||||
template<class VALUE>
|
template<class VALUE>
|
||||||
void exposeBearingFactor(const std::string& name){
|
void exportBearingFactor(const std::string& name){
|
||||||
class_<VALUE>(name, init<>())
|
class_<VALUE>(name, init<>())
|
||||||
;
|
;
|
||||||
}
|
}
|
|
@ -7,7 +7,7 @@ using namespace gtsam;
|
||||||
using namespace std;
|
using namespace std;
|
||||||
|
|
||||||
template<class VALUE>
|
template<class VALUE>
|
||||||
void exposeBetweenFactor(const std::string& name){
|
void exportBetweenFactor(const std::string& name){
|
||||||
class_<VALUE>(name, init<>())
|
class_<VALUE>(name, init<>())
|
||||||
.def(init<Key, Key, VALUE, SharedNoiseModel>())
|
.def(init<Key, Key, VALUE, SharedNoiseModel>())
|
||||||
;
|
;
|
||||||
|
|
|
@ -6,9 +6,9 @@ using namespace gtsam;
|
||||||
|
|
||||||
using namespace std;
|
using namespace std;
|
||||||
|
|
||||||
template<class VALUE>
|
template< class FACTOR, class VALUE >
|
||||||
void exposePriorFactor(const std::string& name){
|
void exportPriorFactor(const std::string& name){
|
||||||
class_<VALUE>(name, init<>())
|
class_< FACTOR >(name.c_str(), init<>())
|
||||||
.def(init<Key, VALUE, SharedNoiseModel>())
|
.def(init< Key, VALUE&, SharedNoiseModel >())
|
||||||
;
|
;
|
||||||
}
|
}
|
|
@ -1,24 +0,0 @@
|
||||||
#include <boost/python.hpp>
|
|
||||||
#include <boost/cstdint.hpp>
|
|
||||||
|
|
||||||
#include <gtsam/geometry/Point2.h>
|
|
||||||
#include <gtsam/geometry/Pose2.h>
|
|
||||||
#include <gtsam/slam/PriorFactor.h>
|
|
||||||
#include <gtsam/slam/BetweenFactor.h>
|
|
||||||
|
|
||||||
template<class VALUE> void exportPriorFactor(const std::string& name);
|
|
||||||
template<class VALUE> void exportBetweenFactor(const std::string& name);
|
|
||||||
|
|
||||||
BOOST_PYTHON_MODULE(libgeometry){
|
|
||||||
using namespace boost::python;
|
|
||||||
|
|
||||||
typedef gtsam::PriorFactor<gtsam::Point2> Point2PriorFactor;
|
|
||||||
typedef gtsam::PriorFactor<gtsam::Pose2> Pose2PriorFactor;
|
|
||||||
|
|
||||||
exportPriorFactor<Point2PriorFactor>("Point2PriorFactor");
|
|
||||||
exportPriorFactor<Pose2PriorFactor>("Pose2PriorFactor");
|
|
||||||
|
|
||||||
typedef gtsam::BetweenFactor<gtsam::Pose2> Pose2BetweenFactor;
|
|
||||||
|
|
||||||
exportBetweenFactor<Pose2BetweenFactor>("Pose2BetweenFactor");
|
|
||||||
}
|
|
Loading…
Reference in New Issue