diff --git a/gtsam/gtsam.i b/gtsam/gtsam.i index 295d5237f..b962724b9 100644 --- a/gtsam/gtsam.i +++ b/gtsam/gtsam.i @@ -2168,6 +2168,7 @@ virtual class NoiseModelFactor: gtsam::NonlinearFactor { #include 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); }; diff --git a/python/gtsam/specializations.h b/python/gtsam/specializations.h index c7f45fc0f..c6efd2f71 100644 --- a/python/gtsam/specializations.h +++ b/python/gtsam/specializations.h @@ -2,9 +2,12 @@ // These are required to save one copy operation on Python calls #ifdef GTSAM_ALLOCATOR_TBB py::bind_vector > >(m_, "KeyVector"); +py::implicitly_convertible > >(); #else py::bind_vector >(m_, "KeyVector"); +py::implicitly_convertible >(); #endif + py::bind_vector > >(m_, "Point2Vector"); py::bind_vector >(m_, "Point3Pairs"); py::bind_vector >(m_, "Pose3Pairs"); diff --git a/python/gtsam/tests/test_custom_factor.py b/python/gtsam/tests/test_custom_factor.py index e8f06b27a..32ae50590 100644 --- a/python/gtsam/tests/test_custom_factor.py +++ b/python/gtsam/tests/test_custom_factor.py @@ -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)