Add a few more template arguments
parent
fa97e5d220
commit
02e2b37b08
|
@ -26,6 +26,7 @@
|
|||
#include "gtsam/geometry/Point3.h"
|
||||
#include "gtsam/geometry/Rot3.h"
|
||||
#include "gtsam/geometry/Pose3.h"
|
||||
#include "gtsam/navigation/ImuBias.h"
|
||||
|
||||
using namespace boost::python;
|
||||
using namespace gtsam;
|
||||
|
@ -88,6 +89,8 @@ 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_vector3) (Key, const gtsam::Vector3&) = &Values::insert;
|
||||
|
||||
|
||||
class_<Values>("Values", init<>())
|
||||
|
@ -110,6 +113,8 @@ void exportValues(){
|
|||
.def("insert", insert_point3)
|
||||
.def("insert", insert_rot3)
|
||||
.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<Point3>, return_internal_reference<>())
|
||||
|
|
|
@ -33,17 +33,17 @@ using namespace gtsam;
|
|||
|
||||
using namespace std;
|
||||
|
||||
// template<class VALUE>
|
||||
// template<class T>
|
||||
// void exportBetweenFactor(const std::string& name){
|
||||
// class_<VALUE>(name, init<>())
|
||||
// .def(init<Key, Key, VALUE, SharedNoiseModel>())
|
||||
// class_<T>(name, init<>())
|
||||
// .def(init<Key, Key, T, SharedNoiseModel>())
|
||||
// ;
|
||||
// }
|
||||
|
||||
#define BETWEENFACTOR(VALUE) \
|
||||
class_< BetweenFactor<VALUE>, bases<NonlinearFactor>, boost::shared_ptr< BetweenFactor<VALUE> > >("BetweenFactor"#VALUE) \
|
||||
.def(init<Key,Key,VALUE,noiseModel::Base::shared_ptr>()) \
|
||||
.def("measured", &BetweenFactor<VALUE>::measured, return_internal_reference<>()) \
|
||||
#define BETWEENFACTOR(T) \
|
||||
class_< BetweenFactor<T>, bases<NonlinearFactor>, boost::shared_ptr< BetweenFactor<T> > >("BetweenFactor"#T) \
|
||||
.def(init<Key,Key,T,noiseModel::Base::shared_ptr>()) \
|
||||
.def("measured", &BetweenFactor<T>::measured, return_internal_reference<>()) \
|
||||
;
|
||||
|
||||
void exportBetweenFactors()
|
||||
|
|
|
@ -54,4 +54,5 @@ void exportPriorFactors()
|
|||
PRIORFACTOR(Point3)
|
||||
PRIORFACTOR(Rot3)
|
||||
PRIORFACTOR(Pose3)
|
||||
PRIORFACTOR(Vector3)
|
||||
}
|
Loading…
Reference in New Issue