Allow KeyVector to just be lists
parent
3638b3745f
commit
66e397cb38
|
|
@ -2168,6 +2168,7 @@ virtual class NoiseModelFactor: gtsam::NonlinearFactor {
|
|||
|
||||
#include <gtsam/nonlinear/CustomFactor.h>
|
||||
virtual class CustomFactor: gtsam::NoiseModelFactor {
|
||||
// Note CustomFactor will not be wrapped for MATLAB, as there is no supporting machinery there.
|
||||
CustomFactor();
|
||||
CustomFactor(const gtsam::SharedNoiseModel& noiseModel, const gtsam::KeyVector& keys, const gtsam::CustomErrorFunction& errorFunction);
|
||||
};
|
||||
|
|
|
|||
|
|
@ -2,9 +2,12 @@
|
|||
// These are required to save one copy operation on Python calls
|
||||
#ifdef GTSAM_ALLOCATOR_TBB
|
||||
py::bind_vector<std::vector<gtsam::Key, tbb::tbb_allocator<gtsam::Key> > >(m_, "KeyVector");
|
||||
py::implicitly_convertible<py::list, std::vector<gtsam::Key, tbb::tbb_allocator<gtsam::Key> > >();
|
||||
#else
|
||||
py::bind_vector<std::vector<gtsam::Key> >(m_, "KeyVector");
|
||||
py::implicitly_convertible<py::list, std::vector<gtsam::Key> >();
|
||||
#endif
|
||||
|
||||
py::bind_vector<std::vector<gtsam::Point2, Eigen::aligned_allocator<gtsam::Point2> > >(m_, "Point2Vector");
|
||||
py::bind_vector<std::vector<gtsam::Point3Pair> >(m_, "Point3Pairs");
|
||||
py::bind_vector<std::vector<gtsam::Pose3Pair> >(m_, "Pose3Pairs");
|
||||
|
|
|
|||
|
|
@ -36,7 +36,7 @@ class TestCustomFactor(GtsamTestCase):
|
|||
return error
|
||||
|
||||
noise_model = gtsam.noiseModel.Unit.Create(3)
|
||||
cf = CustomFactor(noise_model, gtsam.KeyVector([0]), error_func)
|
||||
cf = CustomFactor(noise_model, [0], error_func)
|
||||
v = Values()
|
||||
v.insert(0, Pose2(1, 0, 0))
|
||||
e = cf.error(v)
|
||||
|
|
|
|||
Loading…
Reference in New Issue