From d3d44f9ce0486895527d4671b17473fe71261e4e Mon Sep 17 00:00:00 2001 From: Jose Luis Blanco-Claraco Date: Sun, 17 Dec 2023 00:18:02 +0100 Subject: [PATCH] Update python wrapper --- python/all_mrpt_maps3.cpp | 1 + python/src/mrpt/core/format.cpp | 6 +- python/src/mrpt/maps/CBeacon.cpp | 1 + python/src/mrpt/maps/CColouredOctoMap.cpp | 2 +- .../mrpt/maps/CGasConcentrationGridMap2D.cpp | 2 +- .../src/mrpt/maps/CHeightGridMap2D_Base.cpp | 2 +- python/src/mrpt/maps/CHeightGridMap2D_MRF.cpp | 2 +- python/src/mrpt/maps/CLandmarksMap.cpp | 2 +- python/src/mrpt/maps/CMetricMap.cpp | 3 +- python/src/mrpt/maps/CMetricMap_1.cpp | 6 +- python/src/mrpt/maps/CMultiMetricMap.cpp | 126 +-------------- python/src/mrpt/maps/CMultiMetricMapPDF.cpp | 1 + python/src/mrpt/maps/COccupancyGridMap2D.cpp | 2 +- python/src/mrpt/maps/COccupancyGridMap3D.cpp | 2 +- python/src/mrpt/maps/COctoMap.cpp | 2 +- python/src/mrpt/maps/COctoMapBase.cpp | 3 +- python/src/mrpt/maps/COctoMapBase_1.cpp | 3 +- .../mrpt/maps/CPointCloudFilterByDistance.cpp | 2 +- python/src/mrpt/maps/CPointsMapXYZI.cpp | 2 +- python/src/mrpt/maps/CPointsMap_1.cpp | 2 +- .../src/mrpt/maps/CReflectivityGridMap2D.cpp | 2 +- python/src/mrpt/maps/CSimpleMap.cpp | 148 ++++++++++++++++++ python/src/mrpt/maps/CVoxelMap.cpp | 2 +- python/src/mrpt/maps/CVoxelMapBase.cpp | 6 +- .../mrpt/maps/CVoxelMapOccupancyBase_1.cpp | 3 +- .../mrpt/maps/CVoxelMapOccupancyBase_2.cpp | 3 +- .../src/mrpt/maps/CWirelessPowerGridMap2D.cpp | 2 +- python/src/mrpt/math/TTwist3D.cpp | 1 + .../mrpt/slam/CIncrementalMapPartitioner.cpp | 2 +- python/src/mrpt/slam/CMetricMapBuilder.cpp | 1 + python/src/mrpt/slam/CMetricMapBuilderICP.cpp | 1 + python/src/pymrpt.cpp | 6 +- python/src/pymrpt.sources | 3 +- python/src/unknown/unknown_6.cpp | 12 +- python/src/unknown/unknown_7.cpp | 16 +- python/src/unknown/unknown_8.cpp | 12 +- python/stubs-out/mrpt/pymrpt/mrpt/config.pyi | 2 + python/stubs-out/mrpt/pymrpt/mrpt/maps.pyi | 115 +++++++------- python/stubs-out/mrpt/pymrpt/mrpt/math.pyi | 47 +++++- .../mrpt/pymrpt/mrpt/obs/__init__.pyi | 48 +++++- .../mrpt/pymrpt/mrpt/opengl/__init__.pyi | 12 +- .../mrpt/pymrpt/mrpt/poses/__init__.pyi | 16 ++ 42 files changed, 380 insertions(+), 252 deletions(-) create mode 100644 python/src/mrpt/maps/CSimpleMap.cpp diff --git a/python/all_mrpt_maps3.cpp b/python/all_mrpt_maps3.cpp index c6073548dd..f4d3c42c54 100644 --- a/python/all_mrpt_maps3.cpp +++ b/python/all_mrpt_maps3.cpp @@ -4,6 +4,7 @@ #include "src/mrpt/maps/CRandomFieldGridMap2D.cpp" #include "src/mrpt/maps/CRandomFieldGridMap3D.cpp" #include "src/mrpt/maps/CReflectivityGridMap2D.cpp" +#include "src/mrpt/maps/CSimpleMap.cpp" #include "src/mrpt/maps/CSimplePointsMap.cpp" #include "src/mrpt/maps/CWeightedPointsMap.cpp" #include "src/mrpt/maps/CWirelessPowerGridMap2D.cpp" diff --git a/python/src/mrpt/core/format.cpp b/python/src/mrpt/core/format.cpp index 144154e9a9..a725d5adc0 100644 --- a/python/src/mrpt/core/format.cpp +++ b/python/src/mrpt/core/format.cpp @@ -21,12 +21,12 @@ void bind_mrpt_core_format(std::function< pybind11::module &(std::string const & // mrpt::to_string(double) file:mrpt/core/format.h line:31 M("mrpt").def("to_string", (std::string (*)(double)) &mrpt::to_string, "C++: mrpt::to_string(double) --> std::string", pybind11::arg("v")); - // mrpt::to_string(unsigned long) file:mrpt/core/format.h line:31 - M("mrpt").def("to_string", (std::string (*)(unsigned long)) &mrpt::to_string, "C++: mrpt::to_string(unsigned long) --> std::string", pybind11::arg("v")); - // mrpt::to_string(int) file:mrpt/core/format.h line:31 M("mrpt").def("to_string", (std::string (*)(int)) &mrpt::to_string, "C++: mrpt::to_string(int) --> std::string", pybind11::arg("v")); + // mrpt::to_string(unsigned long) file:mrpt/core/format.h line:31 + M("mrpt").def("to_string", (std::string (*)(unsigned long)) &mrpt::to_string, "C++: mrpt::to_string(unsigned long) --> std::string", pybind11::arg("v")); + // mrpt::to_string(unsigned int) file:mrpt/core/format.h line:31 M("mrpt").def("to_string", (std::string (*)(unsigned int)) &mrpt::to_string, "C++: mrpt::to_string(unsigned int) --> std::string", pybind11::arg("v")); diff --git a/python/src/mrpt/maps/CBeacon.cpp b/python/src/mrpt/maps/CBeacon.cpp index 18745ef11b..9feedf656c 100644 --- a/python/src/mrpt/maps/CBeacon.cpp +++ b/python/src/mrpt/maps/CBeacon.cpp @@ -35,6 +35,7 @@ #include #include #include +#include #include #include #include diff --git a/python/src/mrpt/maps/CColouredOctoMap.cpp b/python/src/mrpt/maps/CColouredOctoMap.cpp index 267f0864df..d84321a45e 100644 --- a/python/src/mrpt/maps/CColouredOctoMap.cpp +++ b/python/src/mrpt/maps/CColouredOctoMap.cpp @@ -39,6 +39,7 @@ #include #include #include +#include #include #include #include @@ -79,7 +80,6 @@ #include #include #include -#include #include #include #include diff --git a/python/src/mrpt/maps/CGasConcentrationGridMap2D.cpp b/python/src/mrpt/maps/CGasConcentrationGridMap2D.cpp index 8c1dfcf1d9..7c31633815 100644 --- a/python/src/mrpt/maps/CGasConcentrationGridMap2D.cpp +++ b/python/src/mrpt/maps/CGasConcentrationGridMap2D.cpp @@ -39,6 +39,7 @@ #include #include #include +#include #include #include #include @@ -73,7 +74,6 @@ #include #include #include -#include #include #include #include diff --git a/python/src/mrpt/maps/CHeightGridMap2D_Base.cpp b/python/src/mrpt/maps/CHeightGridMap2D_Base.cpp index 6b186ccc6f..d92c8455e0 100644 --- a/python/src/mrpt/maps/CHeightGridMap2D_Base.cpp +++ b/python/src/mrpt/maps/CHeightGridMap2D_Base.cpp @@ -43,6 +43,7 @@ #include #include #include +#include #include #include #include @@ -77,7 +78,6 @@ #include #include #include -#include #include #include #include diff --git a/python/src/mrpt/maps/CHeightGridMap2D_MRF.cpp b/python/src/mrpt/maps/CHeightGridMap2D_MRF.cpp index 9ad25e11dc..b9669f8869 100644 --- a/python/src/mrpt/maps/CHeightGridMap2D_MRF.cpp +++ b/python/src/mrpt/maps/CHeightGridMap2D_MRF.cpp @@ -40,6 +40,7 @@ #include #include #include +#include #include #include #include @@ -74,7 +75,6 @@ #include #include #include -#include #include #include #include diff --git a/python/src/mrpt/maps/CLandmarksMap.cpp b/python/src/mrpt/maps/CLandmarksMap.cpp index 5a5dc8fcb9..160d1a3a0f 100644 --- a/python/src/mrpt/maps/CLandmarksMap.cpp +++ b/python/src/mrpt/maps/CLandmarksMap.cpp @@ -37,6 +37,7 @@ #include #include #include +#include #include #include #include @@ -79,7 +80,6 @@ #include #include #include -#include #include #include #include diff --git a/python/src/mrpt/maps/CMetricMap.cpp b/python/src/mrpt/maps/CMetricMap.cpp index 8501ebb7df..8c77e53148 100644 --- a/python/src/mrpt/maps/CMetricMap.cpp +++ b/python/src/mrpt/maps/CMetricMap.cpp @@ -19,6 +19,7 @@ #include #include #include +#include #include #include #include @@ -32,7 +33,6 @@ #include #include #include -#include #include #include #include @@ -40,7 +40,6 @@ #include #include #include -#include #include #include diff --git a/python/src/mrpt/maps/CMetricMap_1.cpp b/python/src/mrpt/maps/CMetricMap_1.cpp index e978d10307..026291b4de 100644 --- a/python/src/mrpt/maps/CMetricMap_1.cpp +++ b/python/src/mrpt/maps/CMetricMap_1.cpp @@ -17,6 +17,7 @@ #include #include #include +#include #include #include #include @@ -28,7 +29,6 @@ #include #include #include -#include #include #include #include @@ -37,7 +37,6 @@ #include #include // __str__ #include -#include #include #include @@ -63,8 +62,7 @@ void bind_mrpt_maps_CMetricMap_1(std::function< pybind11::module &(std::string c cl.def("clear", (void (mrpt::maps::CMetricMap::*)()) &mrpt::maps::CMetricMap::clear, "Erase all the contents of the map \n\nC++: mrpt::maps::CMetricMap::clear() --> void"); cl.def("isEmpty", (bool (mrpt::maps::CMetricMap::*)() const) &mrpt::maps::CMetricMap::isEmpty, "Returns true if the map is empty/no observation has been inserted.\n\nC++: mrpt::maps::CMetricMap::isEmpty() const --> bool"); cl.def("boundingBox", (struct mrpt::math::TBoundingBox_ (mrpt::maps::CMetricMap::*)() const) &mrpt::maps::CMetricMap::boundingBox, "Returns the bounding box of the metric map, or (0,0,0)-(0,0,0) (the\n default value of mrpt::math::TBoundingBoxf() if not implemented in the\n derived class or the map is empty.\n\nC++: mrpt::maps::CMetricMap::boundingBox() const --> struct mrpt::math::TBoundingBox_"); - cl.def("loadFromProbabilisticPosesAndObservations", (void (mrpt::maps::CMetricMap::*)(const class mrpt::maps::CSimpleMap &)) &mrpt::maps::CMetricMap::loadFromProbabilisticPosesAndObservations, "Load the map contents from a CSimpleMap object, erasing all previous\n content of the map. This is done invoking `insertObservation()` for each\n observation at the mean 3D robot pose of each pose-observations pair in\n the CSimpleMap object.\n\n \n insertObservation, CSimpleMap\n \n\n std::exception Some internal steps in invoked methods can\n raise exceptions on invalid parameters, etc...\n\nC++: mrpt::maps::CMetricMap::loadFromProbabilisticPosesAndObservations(const class mrpt::maps::CSimpleMap &) --> void", pybind11::arg("Map")); - cl.def("loadFromSimpleMap", (void (mrpt::maps::CMetricMap::*)(const class mrpt::maps::CSimpleMap &)) &mrpt::maps::CMetricMap::loadFromSimpleMap, "! \n\nC++: mrpt::maps::CMetricMap::loadFromSimpleMap(const class mrpt::maps::CSimpleMap &) --> void", pybind11::arg("Map")); + cl.def("loadFromSimpleMap", (void (mrpt::maps::CMetricMap::*)(const class mrpt::maps::CSimpleMap &)) &mrpt::maps::CMetricMap::loadFromSimpleMap, "Load the map contents from a CSimpleMap object, erasing all previous\n content of the map. This is done invoking `insertObservation()` for each\n observation at the mean 3D robot pose of each pose-observations pair in\n the CSimpleMap object.\n\n \n insertObservation, CSimpleMap\n \n\n std::exception Some internal steps in invoked methods can\n raise exceptions on invalid parameters, etc...\n\nC++: mrpt::maps::CMetricMap::loadFromSimpleMap(const class mrpt::maps::CSimpleMap &) --> void", pybind11::arg("Map")); cl.def("insertObs", [](mrpt::maps::CMetricMap &o, const class mrpt::obs::CObservation & a0) -> bool { return o.insertObs(a0); }, "", pybind11::arg("obs")); cl.def("insertObs", (bool (mrpt::maps::CMetricMap::*)(const class mrpt::obs::CObservation &, const class mrpt::poses::CPose3D *)) &mrpt::maps::CMetricMap::insertObs, "C++: mrpt::maps::CMetricMap::insertObs(const class mrpt::obs::CObservation &, const class mrpt::poses::CPose3D *) --> bool", pybind11::arg("obs"), pybind11::arg("robotPose")); cl.def("insertObs", [](mrpt::maps::CMetricMap &o, const class mrpt::obs::CSensoryFrame & a0) -> bool { return o.insertObs(a0); }, "", pybind11::arg("sf")); diff --git a/python/src/mrpt/maps/CMultiMetricMap.cpp b/python/src/mrpt/maps/CMultiMetricMap.cpp index b97a5246d0..783b5ec1e6 100644 --- a/python/src/mrpt/maps/CMultiMetricMap.cpp +++ b/python/src/mrpt/maps/CMultiMetricMap.cpp @@ -37,6 +37,7 @@ #include #include #include +#include #include #include #include @@ -75,7 +76,6 @@ #include #include #include -#include #include #include #include @@ -361,77 +361,6 @@ struct PyCallBack_mrpt_maps_CMultiMetricMap : public mrpt::maps::CMultiMetricMap } }; -// mrpt::maps::CSimpleMap file:mrpt/maps/CSimpleMap.h line:43 -struct PyCallBack_mrpt_maps_CSimpleMap : public mrpt::maps::CSimpleMap { - using mrpt::maps::CSimpleMap::CSimpleMap; - - const struct mrpt::rtti::TRuntimeClassId * GetRuntimeClass() const override { - pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "GetRuntimeClass"); - if (overload) { - auto o = overload.operator()(); - if (pybind11::detail::cast_is_temporary_value_reference::value) { - static pybind11::detail::override_caster_t caster; - return pybind11::detail::cast_ref(std::move(o), caster); - } - else return pybind11::detail::cast_safe(std::move(o)); - } - return CSimpleMap::GetRuntimeClass(); - } - class mrpt::rtti::CObject * clone() const override { - pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "clone"); - if (overload) { - auto o = overload.operator()(); - if (pybind11::detail::cast_is_temporary_value_reference::value) { - static pybind11::detail::override_caster_t caster; - return pybind11::detail::cast_ref(std::move(o), caster); - } - else return pybind11::detail::cast_safe(std::move(o)); - } - return CSimpleMap::clone(); - } - uint8_t serializeGetVersion() const override { - pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "serializeGetVersion"); - if (overload) { - auto o = overload.operator()(); - if (pybind11::detail::cast_is_temporary_value_reference::value) { - static pybind11::detail::override_caster_t caster; - return pybind11::detail::cast_ref(std::move(o), caster); - } - else return pybind11::detail::cast_safe(std::move(o)); - } - return CSimpleMap::serializeGetVersion(); - } - void serializeTo(class mrpt::serialization::CArchive & a0) const override { - pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "serializeTo"); - if (overload) { - auto o = overload.operator()(a0); - if (pybind11::detail::cast_is_temporary_value_reference::value) { - static pybind11::detail::override_caster_t caster; - return pybind11::detail::cast_ref(std::move(o), caster); - } - else return pybind11::detail::cast_safe(std::move(o)); - } - return CSimpleMap::serializeTo(a0); - } - void serializeFrom(class mrpt::serialization::CArchive & a0, uint8_t a1) override { - pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "serializeFrom"); - if (overload) { - auto o = overload.operator()(a0, a1); - if (pybind11::detail::cast_is_temporary_value_reference::value) { - static pybind11::detail::override_caster_t caster; - return pybind11::detail::cast_ref(std::move(o), caster); - } - else return pybind11::detail::cast_safe(std::move(o)); - } - return CSimpleMap::serializeFrom(a0, a1); - } -}; - void bind_mrpt_maps_CMultiMetricMap(std::function< pybind11::module &(std::string const &namespace_) > &M) { { // mrpt::maps::CMultiMetricMap file:mrpt/maps/CMultiMetricMap.h line:120 @@ -458,57 +387,4 @@ void bind_mrpt_maps_CMultiMetricMap(std::function< pybind11::module &(std::strin cl.def("getAsSimplePointsMap", (const class mrpt::maps::CSimplePointsMap * (mrpt::maps::CMultiMetricMap::*)() const) &mrpt::maps::CMultiMetricMap::getAsSimplePointsMap, "C++: mrpt::maps::CMultiMetricMap::getAsSimplePointsMap() const --> const class mrpt::maps::CSimplePointsMap *", pybind11::return_value_policy::automatic); cl.def("asString", (std::string (mrpt::maps::CMultiMetricMap::*)() const) &mrpt::maps::CMultiMetricMap::asString, "Returns a short description of the map. \n\nC++: mrpt::maps::CMultiMetricMap::asString() const --> std::string"); } - { // mrpt::maps::CSimpleMap file:mrpt/maps/CSimpleMap.h line:43 - pybind11::class_, PyCallBack_mrpt_maps_CSimpleMap, mrpt::serialization::CSerializable> cl(M("mrpt::maps"), "CSimpleMap", "A view-based representation of a metric map.\n\n This comprises a list of `` pairs, that is,\n the **poses** (keyframes) from which a set of **observations** where\n gathered:\n - Poses, in the global `map` frame of reference, are stored as probabilistic\n PDFs over SE(3) as instances of mrpt::poses::CPose3DPDF\n - Observations are stored as mrpt::obs::CSensoryFrame.\n\n Note that in order to generate an actual metric map (occupancy grid, point\n cloud, octomap, etc.) from a \"simple map\", you must instantiate the desired\n metric map class and invoke its virtual method\n mrpt::maps::CMetricMap::loadFromProbabilisticPosesAndObservations().\n\n \n Objects of this class are serialized into GZ-compressed\n files with the extension `.simplemap`.\n See [Robotics file formats](robotics_file_formats.html).\n\n \n mrpt::obs::CSensoryFrame, mrpt::poses::CPose3DPDF, mrpt::maps::CMetricMap\n\n \n\n "); - cl.def( pybind11::init( [](){ return new mrpt::maps::CSimpleMap(); }, [](){ return new PyCallBack_mrpt_maps_CSimpleMap(); } ) ); - cl.def( pybind11::init( [](PyCallBack_mrpt_maps_CSimpleMap const &o){ return new PyCallBack_mrpt_maps_CSimpleMap(o); } ) ); - cl.def( pybind11::init( [](mrpt::maps::CSimpleMap const &o){ return new mrpt::maps::CSimpleMap(o); } ) ); - cl.def_static("GetRuntimeClassIdStatic", (const struct mrpt::rtti::TRuntimeClassId & (*)()) &mrpt::maps::CSimpleMap::GetRuntimeClassIdStatic, "C++: mrpt::maps::CSimpleMap::GetRuntimeClassIdStatic() --> const struct mrpt::rtti::TRuntimeClassId &", pybind11::return_value_policy::automatic); - cl.def("GetRuntimeClass", (const struct mrpt::rtti::TRuntimeClassId * (mrpt::maps::CSimpleMap::*)() const) &mrpt::maps::CSimpleMap::GetRuntimeClass, "C++: mrpt::maps::CSimpleMap::GetRuntimeClass() const --> const struct mrpt::rtti::TRuntimeClassId *", pybind11::return_value_policy::automatic); - cl.def("clone", (class mrpt::rtti::CObject * (mrpt::maps::CSimpleMap::*)() const) &mrpt::maps::CSimpleMap::clone, "C++: mrpt::maps::CSimpleMap::clone() const --> class mrpt::rtti::CObject *", pybind11::return_value_policy::automatic); - cl.def_static("CreateObject", (class std::shared_ptr (*)()) &mrpt::maps::CSimpleMap::CreateObject, "C++: mrpt::maps::CSimpleMap::CreateObject() --> class std::shared_ptr"); - cl.def("assign", (class mrpt::maps::CSimpleMap & (mrpt::maps::CSimpleMap::*)(const class mrpt::maps::CSimpleMap &)) &mrpt::maps::CSimpleMap::operator=, "Copy, making a deep copy of all data. \n\nC++: mrpt::maps::CSimpleMap::operator=(const class mrpt::maps::CSimpleMap &) --> class mrpt::maps::CSimpleMap &", pybind11::return_value_policy::automatic, pybind11::arg("o")); - cl.def("saveToFile", (bool (mrpt::maps::CSimpleMap::*)(const std::string &) const) &mrpt::maps::CSimpleMap::saveToFile, "Save this object to a .simplemap binary file (compressed with gzip)\n See [Robotics file formats](robotics_file_formats.html).\n \n\n loadFromFile()\n \n\n false on any error. \n\nC++: mrpt::maps::CSimpleMap::saveToFile(const std::string &) const --> bool", pybind11::arg("filName")); - cl.def("loadFromFile", (bool (mrpt::maps::CSimpleMap::*)(const std::string &)) &mrpt::maps::CSimpleMap::loadFromFile, "Load the contents of this object from a .simplemap binary file (possibly\n compressed with gzip)\n See [Robotics file formats](robotics_file_formats.html).\n \n\n saveToFile()\n \n\n false on any error. \n\nC++: mrpt::maps::CSimpleMap::loadFromFile(const std::string &) --> bool", pybind11::arg("filName")); - cl.def("size", (size_t (mrpt::maps::CSimpleMap::*)() const) &mrpt::maps::CSimpleMap::size, "Returns the count of (pose,sensoryFrame) pairs \n\nC++: mrpt::maps::CSimpleMap::size() const --> size_t"); - cl.def("empty", (bool (mrpt::maps::CSimpleMap::*)() const) &mrpt::maps::CSimpleMap::empty, "Returns size()!=0 \n\nC++: mrpt::maps::CSimpleMap::empty() const --> bool"); - cl.def("get", (void (mrpt::maps::CSimpleMap::*)(size_t, class std::shared_ptr &, class std::shared_ptr &) const) &mrpt::maps::CSimpleMap::get, "Access to the 0-based index i'th pair.\n \n\n std::exception On index out of bounds.\n\nC++: mrpt::maps::CSimpleMap::get(size_t, class std::shared_ptr &, class std::shared_ptr &) const --> void", pybind11::arg("index"), pybind11::arg("out_posePDF"), pybind11::arg("out_SF")); - cl.def("getAsPair", (struct mrpt::maps::CSimpleMap::Pair & (mrpt::maps::CSimpleMap::*)(size_t)) &mrpt::maps::CSimpleMap::getAsPair, "C++: mrpt::maps::CSimpleMap::getAsPair(size_t) --> struct mrpt::maps::CSimpleMap::Pair &", pybind11::return_value_policy::automatic, pybind11::arg("index")); - cl.def("get", (void (mrpt::maps::CSimpleMap::*)(size_t, class std::shared_ptr &, class std::shared_ptr &)) &mrpt::maps::CSimpleMap::get, "C++: mrpt::maps::CSimpleMap::get(size_t, class std::shared_ptr &, class std::shared_ptr &) --> void", pybind11::arg("index"), pybind11::arg("out_posePDF"), pybind11::arg("out_SF")); - cl.def("get", (class std::tuple, class std::shared_ptr > (mrpt::maps::CSimpleMap::*)(size_t)) &mrpt::maps::CSimpleMap::get, "C++: mrpt::maps::CSimpleMap::get(size_t) --> class std::tuple, class std::shared_ptr >", pybind11::arg("index")); - cl.def("set", (void (mrpt::maps::CSimpleMap::*)(size_t, const class std::shared_ptr &, const class std::shared_ptr &)) &mrpt::maps::CSimpleMap::set, "Changes the 0-based index i'th pair.\n If one of either `in_posePDF` or `in_SF` are empty `shared_ptr`s, the\n corresponding field in the map is not modified.\n\n \n std::exception On index out of bounds.\n \n\n insert, get, remove\n\nC++: mrpt::maps::CSimpleMap::set(size_t, const class std::shared_ptr &, const class std::shared_ptr &) --> void", pybind11::arg("index"), pybind11::arg("in_posePDF"), pybind11::arg("in_SF")); - cl.def("set", (void (mrpt::maps::CSimpleMap::*)(size_t, const struct mrpt::maps::CSimpleMap::Pair &)) &mrpt::maps::CSimpleMap::set, "C++: mrpt::maps::CSimpleMap::set(size_t, const struct mrpt::maps::CSimpleMap::Pair &) --> void", pybind11::arg("index"), pybind11::arg("poseSF")); - cl.def("set", (void (mrpt::maps::CSimpleMap::*)(size_t, const class std::shared_ptr &, const class std::shared_ptr &)) &mrpt::maps::CSimpleMap::set, "C++: mrpt::maps::CSimpleMap::set(size_t, const class std::shared_ptr &, const class std::shared_ptr &) --> void", pybind11::arg("index"), pybind11::arg("in_posePDF"), pybind11::arg("in_SF")); - cl.def("remove", (void (mrpt::maps::CSimpleMap::*)(size_t)) &mrpt::maps::CSimpleMap::remove, "Deletes the 0-based index i'th pair.\n \n\n std::exception On index out of bounds.\n \n\n insert, get, set\n\nC++: mrpt::maps::CSimpleMap::remove(size_t) --> void", pybind11::arg("index")); - cl.def("insert", (void (mrpt::maps::CSimpleMap::*)(const class mrpt::poses::CPose3DPDF &, const class mrpt::obs::CSensoryFrame &)) &mrpt::maps::CSimpleMap::insert, "Adds a new keyframe (SE(3) pose) to the view-based map, making a deep\n copy of the pose PDF (observations within the SF are always copied as\n `shared_ptr`s).\n\nC++: mrpt::maps::CSimpleMap::insert(const class mrpt::poses::CPose3DPDF &, const class mrpt::obs::CSensoryFrame &) --> void", pybind11::arg("in_posePDF"), pybind11::arg("in_SF")); - cl.def("insert", (void (mrpt::maps::CSimpleMap::*)(const class std::shared_ptr &, const class std::shared_ptr &)) &mrpt::maps::CSimpleMap::insert, "Adds a new keyframe (SE(3) pose) to the view-based map.\n Both shared pointers are copied (shallow object copies).\n\nC++: mrpt::maps::CSimpleMap::insert(const class std::shared_ptr &, const class std::shared_ptr &) --> void", pybind11::arg("in_posePDF"), pybind11::arg("in_SF")); - cl.def("insert", (void (mrpt::maps::CSimpleMap::*)(const struct mrpt::maps::CSimpleMap::Pair &)) &mrpt::maps::CSimpleMap::insert, "C++: mrpt::maps::CSimpleMap::insert(const struct mrpt::maps::CSimpleMap::Pair &) --> void", pybind11::arg("poseSF")); - cl.def("insert", (void (mrpt::maps::CSimpleMap::*)(const class mrpt::poses::CPosePDF &, const class mrpt::obs::CSensoryFrame &)) &mrpt::maps::CSimpleMap::insert, "Adds a new keyframe (SE(2) pose) to the view-based map, making a deep\n copy of the pose PDF (observations within the SF are always copied as\n `shared_ptr`s).\n\nC++: mrpt::maps::CSimpleMap::insert(const class mrpt::poses::CPosePDF &, const class mrpt::obs::CSensoryFrame &) --> void", pybind11::arg("in_posePDF"), pybind11::arg("in_SF")); - cl.def("insert", (void (mrpt::maps::CSimpleMap::*)(const class std::shared_ptr &, const class std::shared_ptr &)) &mrpt::maps::CSimpleMap::insert, "Adds a new keyframe (SE(2) pose) to the view-based map.\n Both shared pointers are copied (shallow object copies).\n\nC++: mrpt::maps::CSimpleMap::insert(const class std::shared_ptr &, const class std::shared_ptr &) --> void", pybind11::arg("in_posePDF"), pybind11::arg("in_SF")); - cl.def("clear", (void (mrpt::maps::CSimpleMap::*)()) &mrpt::maps::CSimpleMap::clear, "Remove all stored pairs. \n remove \n\nC++: mrpt::maps::CSimpleMap::clear() --> void"); - cl.def("changeCoordinatesOrigin", (void (mrpt::maps::CSimpleMap::*)(const class mrpt::poses::CPose3D &)) &mrpt::maps::CSimpleMap::changeCoordinatesOrigin, "Change the coordinate origin of all stored poses, that is, translates\n and rotates the map such that the old SE(3) origin (identity\n transformation) becomes the new provided one.\n\nC++: mrpt::maps::CSimpleMap::changeCoordinatesOrigin(const class mrpt::poses::CPose3D &) --> void", pybind11::arg("newOrigin")); - - { // mrpt::maps::CSimpleMap::Pair file:mrpt/maps/CSimpleMap.h line:56 - auto & enclosing_class = cl; - pybind11::class_> cl(enclosing_class, "Pair", ""); - cl.def( pybind11::init( [](){ return new mrpt::maps::CSimpleMap::Pair(); } ) ); - cl.def( pybind11::init( [](mrpt::maps::CSimpleMap::Pair const &o){ return new mrpt::maps::CSimpleMap::Pair(o); } ) ); - cl.def_readwrite("pose", &mrpt::maps::CSimpleMap::Pair::pose); - cl.def_readwrite("sf", &mrpt::maps::CSimpleMap::Pair::sf); - cl.def("assign", (struct mrpt::maps::CSimpleMap::Pair & (mrpt::maps::CSimpleMap::Pair::*)(const struct mrpt::maps::CSimpleMap::Pair &)) &mrpt::maps::CSimpleMap::Pair::operator=, "C++: mrpt::maps::CSimpleMap::Pair::operator=(const struct mrpt::maps::CSimpleMap::Pair &) --> struct mrpt::maps::CSimpleMap::Pair &", pybind11::return_value_policy::automatic, pybind11::arg("")); - } - - { // mrpt::maps::CSimpleMap::ConstPair file:mrpt/maps/CSimpleMap.h line:65 - auto & enclosing_class = cl; - pybind11::class_> cl(enclosing_class, "ConstPair", ""); - cl.def( pybind11::init( [](){ return new mrpt::maps::CSimpleMap::ConstPair(); } ) ); - cl.def( pybind11::init(), pybind11::arg("p") ); - - cl.def( pybind11::init( [](mrpt::maps::CSimpleMap::ConstPair const &o){ return new mrpt::maps::CSimpleMap::ConstPair(o); } ) ); - cl.def_readwrite("pose", &mrpt::maps::CSimpleMap::ConstPair::pose); - cl.def_readwrite("sf", &mrpt::maps::CSimpleMap::ConstPair::sf); - cl.def("assign", (struct mrpt::maps::CSimpleMap::ConstPair & (mrpt::maps::CSimpleMap::ConstPair::*)(const struct mrpt::maps::CSimpleMap::ConstPair &)) &mrpt::maps::CSimpleMap::ConstPair::operator=, "C++: mrpt::maps::CSimpleMap::ConstPair::operator=(const struct mrpt::maps::CSimpleMap::ConstPair &) --> struct mrpt::maps::CSimpleMap::ConstPair &", pybind11::return_value_policy::automatic, pybind11::arg("")); - } - - } } diff --git a/python/src/mrpt/maps/CMultiMetricMapPDF.cpp b/python/src/mrpt/maps/CMultiMetricMapPDF.cpp index e6b7d92b80..0318ba2527 100644 --- a/python/src/mrpt/maps/CMultiMetricMapPDF.cpp +++ b/python/src/mrpt/maps/CMultiMetricMapPDF.cpp @@ -24,6 +24,7 @@ #include #include #include +#include #include #include #include diff --git a/python/src/mrpt/maps/COccupancyGridMap2D.cpp b/python/src/mrpt/maps/COccupancyGridMap2D.cpp index 9ba6f5aec2..6e5ee4fce2 100644 --- a/python/src/mrpt/maps/COccupancyGridMap2D.cpp +++ b/python/src/mrpt/maps/COccupancyGridMap2D.cpp @@ -41,6 +41,7 @@ #include #include #include +#include #include #include #include @@ -78,7 +79,6 @@ #include #include #include -#include #include #include #include diff --git a/python/src/mrpt/maps/COccupancyGridMap3D.cpp b/python/src/mrpt/maps/COccupancyGridMap3D.cpp index 72772ebc28..3a791eb55b 100644 --- a/python/src/mrpt/maps/COccupancyGridMap3D.cpp +++ b/python/src/mrpt/maps/COccupancyGridMap3D.cpp @@ -35,6 +35,7 @@ #include #include #include +#include #include #include #include @@ -71,7 +72,6 @@ #include #include #include -#include #include #include #include diff --git a/python/src/mrpt/maps/COctoMap.cpp b/python/src/mrpt/maps/COctoMap.cpp index 0d0a72f709..b48883b808 100644 --- a/python/src/mrpt/maps/COctoMap.cpp +++ b/python/src/mrpt/maps/COctoMap.cpp @@ -39,6 +39,7 @@ #include #include #include +#include #include #include #include @@ -78,7 +79,6 @@ #include #include #include -#include #include #include #include diff --git a/python/src/mrpt/maps/COctoMapBase.cpp b/python/src/mrpt/maps/COctoMapBase.cpp index c08e39eb80..6118923961 100644 --- a/python/src/mrpt/maps/COctoMapBase.cpp +++ b/python/src/mrpt/maps/COctoMapBase.cpp @@ -166,8 +166,7 @@ void bind_mrpt_maps_COctoMapBase(std::function< pybind11::module &(std::string c cl.def("clear", (void (mrpt::maps::CMetricMap::*)()) &mrpt::maps::CMetricMap::clear, "Erase all the contents of the map \n\nC++: mrpt::maps::CMetricMap::clear() --> void"); cl.def("isEmpty", (bool (mrpt::maps::CMetricMap::*)() const) &mrpt::maps::CMetricMap::isEmpty, "Returns true if the map is empty/no observation has been inserted.\n\nC++: mrpt::maps::CMetricMap::isEmpty() const --> bool"); cl.def("boundingBox", (struct mrpt::math::TBoundingBox_ (mrpt::maps::CMetricMap::*)() const) &mrpt::maps::CMetricMap::boundingBox, "Returns the bounding box of the metric map, or (0,0,0)-(0,0,0) (the\n default value of mrpt::math::TBoundingBoxf() if not implemented in the\n derived class or the map is empty.\n\nC++: mrpt::maps::CMetricMap::boundingBox() const --> struct mrpt::math::TBoundingBox_"); - cl.def("loadFromProbabilisticPosesAndObservations", (void (mrpt::maps::CMetricMap::*)(const class mrpt::maps::CSimpleMap &)) &mrpt::maps::CMetricMap::loadFromProbabilisticPosesAndObservations, "Load the map contents from a CSimpleMap object, erasing all previous\n content of the map. This is done invoking `insertObservation()` for each\n observation at the mean 3D robot pose of each pose-observations pair in\n the CSimpleMap object.\n\n \n insertObservation, CSimpleMap\n \n\n std::exception Some internal steps in invoked methods can\n raise exceptions on invalid parameters, etc...\n\nC++: mrpt::maps::CMetricMap::loadFromProbabilisticPosesAndObservations(const class mrpt::maps::CSimpleMap &) --> void", pybind11::arg("Map")); - cl.def("loadFromSimpleMap", (void (mrpt::maps::CMetricMap::*)(const class mrpt::maps::CSimpleMap &)) &mrpt::maps::CMetricMap::loadFromSimpleMap, "! \n\nC++: mrpt::maps::CMetricMap::loadFromSimpleMap(const class mrpt::maps::CSimpleMap &) --> void", pybind11::arg("Map")); + cl.def("loadFromSimpleMap", (void (mrpt::maps::CMetricMap::*)(const class mrpt::maps::CSimpleMap &)) &mrpt::maps::CMetricMap::loadFromSimpleMap, "Load the map contents from a CSimpleMap object, erasing all previous\n content of the map. This is done invoking `insertObservation()` for each\n observation at the mean 3D robot pose of each pose-observations pair in\n the CSimpleMap object.\n\n \n insertObservation, CSimpleMap\n \n\n std::exception Some internal steps in invoked methods can\n raise exceptions on invalid parameters, etc...\n\nC++: mrpt::maps::CMetricMap::loadFromSimpleMap(const class mrpt::maps::CSimpleMap &) --> void", pybind11::arg("Map")); cl.def("insertObs", [](mrpt::maps::CMetricMap &o, const class mrpt::obs::CObservation & a0) -> bool { return o.insertObs(a0); }, "", pybind11::arg("obs")); cl.def("insertObs", (bool (mrpt::maps::CMetricMap::*)(const class mrpt::obs::CObservation &, const class mrpt::poses::CPose3D *)) &mrpt::maps::CMetricMap::insertObs, "C++: mrpt::maps::CMetricMap::insertObs(const class mrpt::obs::CObservation &, const class mrpt::poses::CPose3D *) --> bool", pybind11::arg("obs"), pybind11::arg("robotPose")); cl.def("insertObs", [](mrpt::maps::CMetricMap &o, const class mrpt::obs::CSensoryFrame & a0) -> bool { return o.insertObs(a0); }, "", pybind11::arg("sf")); diff --git a/python/src/mrpt/maps/COctoMapBase_1.cpp b/python/src/mrpt/maps/COctoMapBase_1.cpp index 265b29995f..faa8b45bfb 100644 --- a/python/src/mrpt/maps/COctoMapBase_1.cpp +++ b/python/src/mrpt/maps/COctoMapBase_1.cpp @@ -166,8 +166,7 @@ void bind_mrpt_maps_COctoMapBase_1(std::function< pybind11::module &(std::string cl.def("clear", (void (mrpt::maps::CMetricMap::*)()) &mrpt::maps::CMetricMap::clear, "Erase all the contents of the map \n\nC++: mrpt::maps::CMetricMap::clear() --> void"); cl.def("isEmpty", (bool (mrpt::maps::CMetricMap::*)() const) &mrpt::maps::CMetricMap::isEmpty, "Returns true if the map is empty/no observation has been inserted.\n\nC++: mrpt::maps::CMetricMap::isEmpty() const --> bool"); cl.def("boundingBox", (struct mrpt::math::TBoundingBox_ (mrpt::maps::CMetricMap::*)() const) &mrpt::maps::CMetricMap::boundingBox, "Returns the bounding box of the metric map, or (0,0,0)-(0,0,0) (the\n default value of mrpt::math::TBoundingBoxf() if not implemented in the\n derived class or the map is empty.\n\nC++: mrpt::maps::CMetricMap::boundingBox() const --> struct mrpt::math::TBoundingBox_"); - cl.def("loadFromProbabilisticPosesAndObservations", (void (mrpt::maps::CMetricMap::*)(const class mrpt::maps::CSimpleMap &)) &mrpt::maps::CMetricMap::loadFromProbabilisticPosesAndObservations, "Load the map contents from a CSimpleMap object, erasing all previous\n content of the map. This is done invoking `insertObservation()` for each\n observation at the mean 3D robot pose of each pose-observations pair in\n the CSimpleMap object.\n\n \n insertObservation, CSimpleMap\n \n\n std::exception Some internal steps in invoked methods can\n raise exceptions on invalid parameters, etc...\n\nC++: mrpt::maps::CMetricMap::loadFromProbabilisticPosesAndObservations(const class mrpt::maps::CSimpleMap &) --> void", pybind11::arg("Map")); - cl.def("loadFromSimpleMap", (void (mrpt::maps::CMetricMap::*)(const class mrpt::maps::CSimpleMap &)) &mrpt::maps::CMetricMap::loadFromSimpleMap, "! \n\nC++: mrpt::maps::CMetricMap::loadFromSimpleMap(const class mrpt::maps::CSimpleMap &) --> void", pybind11::arg("Map")); + cl.def("loadFromSimpleMap", (void (mrpt::maps::CMetricMap::*)(const class mrpt::maps::CSimpleMap &)) &mrpt::maps::CMetricMap::loadFromSimpleMap, "Load the map contents from a CSimpleMap object, erasing all previous\n content of the map. This is done invoking `insertObservation()` for each\n observation at the mean 3D robot pose of each pose-observations pair in\n the CSimpleMap object.\n\n \n insertObservation, CSimpleMap\n \n\n std::exception Some internal steps in invoked methods can\n raise exceptions on invalid parameters, etc...\n\nC++: mrpt::maps::CMetricMap::loadFromSimpleMap(const class mrpt::maps::CSimpleMap &) --> void", pybind11::arg("Map")); cl.def("insertObs", [](mrpt::maps::CMetricMap &o, const class mrpt::obs::CObservation & a0) -> bool { return o.insertObs(a0); }, "", pybind11::arg("obs")); cl.def("insertObs", (bool (mrpt::maps::CMetricMap::*)(const class mrpt::obs::CObservation &, const class mrpt::poses::CPose3D *)) &mrpt::maps::CMetricMap::insertObs, "C++: mrpt::maps::CMetricMap::insertObs(const class mrpt::obs::CObservation &, const class mrpt::poses::CPose3D *) --> bool", pybind11::arg("obs"), pybind11::arg("robotPose")); cl.def("insertObs", [](mrpt::maps::CMetricMap &o, const class mrpt::obs::CSensoryFrame & a0) -> bool { return o.insertObs(a0); }, "", pybind11::arg("sf")); diff --git a/python/src/mrpt/maps/CPointCloudFilterByDistance.cpp b/python/src/mrpt/maps/CPointCloudFilterByDistance.cpp index fac1e6cf8f..04ec6cc83b 100644 --- a/python/src/mrpt/maps/CPointCloudFilterByDistance.cpp +++ b/python/src/mrpt/maps/CPointCloudFilterByDistance.cpp @@ -39,6 +39,7 @@ #include #include #include +#include #include #include #include @@ -77,7 +78,6 @@ #include #include #include -#include #include #include #include diff --git a/python/src/mrpt/maps/CPointsMapXYZI.cpp b/python/src/mrpt/maps/CPointsMapXYZI.cpp index 0730248630..ca257d79ca 100644 --- a/python/src/mrpt/maps/CPointsMapXYZI.cpp +++ b/python/src/mrpt/maps/CPointsMapXYZI.cpp @@ -32,7 +32,7 @@ void bind_mrpt_maps_CPointsMapXYZI(std::function< pybind11::module &(std::string const &namespace_) > &M) { - { // mrpt::opengl::PointCloudAdapter file:mrpt/maps/CPointsMapXYZI.h line:304 + { // mrpt::opengl::PointCloudAdapter file:mrpt/maps/CPointsMapXYZI.h line:309 pybind11::class_, std::shared_ptr>> cl(M("mrpt::opengl"), "PointCloudAdapter_mrpt_maps_CPointsMapXYZI_t", "Specialization\n mrpt::opengl::PointCloudAdapter\n \n"); cl.def( pybind11::init(), pybind11::arg("obj") ); diff --git a/python/src/mrpt/maps/CPointsMap_1.cpp b/python/src/mrpt/maps/CPointsMap_1.cpp index 3fcae64cb3..bbc956bd98 100644 --- a/python/src/mrpt/maps/CPointsMap_1.cpp +++ b/python/src/mrpt/maps/CPointsMap_1.cpp @@ -39,7 +39,7 @@ void bind_mrpt_maps_CPointsMap_1(std::function< pybind11::module &(std::string const &namespace_) > &M) { - { // mrpt::opengl::PointCloudAdapter file:mrpt/maps/CPointsMap.h line:1254 + { // mrpt::opengl::PointCloudAdapter file:mrpt/maps/CPointsMap.h line:1291 pybind11::class_, std::shared_ptr>> cl(M("mrpt::opengl"), "PointCloudAdapter_mrpt_maps_CPointsMap_t", "Specialization mrpt::opengl::PointCloudAdapter\n \n"); cl.def( pybind11::init(), pybind11::arg("obj") ); diff --git a/python/src/mrpt/maps/CReflectivityGridMap2D.cpp b/python/src/mrpt/maps/CReflectivityGridMap2D.cpp index 09244fb041..a86a2c0bd3 100644 --- a/python/src/mrpt/maps/CReflectivityGridMap2D.cpp +++ b/python/src/mrpt/maps/CReflectivityGridMap2D.cpp @@ -42,6 +42,7 @@ #include #include #include +#include #include #include #include @@ -80,7 +81,6 @@ #include #include #include -#include #include #include #include diff --git a/python/src/mrpt/maps/CSimpleMap.cpp b/python/src/mrpt/maps/CSimpleMap.cpp new file mode 100644 index 0000000000..ece5108608 --- /dev/null +++ b/python/src/mrpt/maps/CSimpleMap.cpp @@ -0,0 +1,148 @@ +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include // __str__ +#include +#include + +#include +#include +#include +#include + + +#ifndef BINDER_PYBIND11_TYPE_CASTER + #define BINDER_PYBIND11_TYPE_CASTER + PYBIND11_DECLARE_HOLDER_TYPE(T, std::shared_ptr) + PYBIND11_DECLARE_HOLDER_TYPE(T, T*) + PYBIND11_MAKE_OPAQUE(std::shared_ptr) +#endif + +// mrpt::maps::CSimpleMap file:mrpt/maps/CSimpleMap.h line:57 +struct PyCallBack_mrpt_maps_CSimpleMap : public mrpt::maps::CSimpleMap { + using mrpt::maps::CSimpleMap::CSimpleMap; + + const struct mrpt::rtti::TRuntimeClassId * GetRuntimeClass() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "GetRuntimeClass"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CSimpleMap::GetRuntimeClass(); + } + class mrpt::rtti::CObject * clone() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "clone"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CSimpleMap::clone(); + } + uint8_t serializeGetVersion() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "serializeGetVersion"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CSimpleMap::serializeGetVersion(); + } + void serializeTo(class mrpt::serialization::CArchive & a0) const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "serializeTo"); + if (overload) { + auto o = overload.operator()(a0); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CSimpleMap::serializeTo(a0); + } + void serializeFrom(class mrpt::serialization::CArchive & a0, uint8_t a1) override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "serializeFrom"); + if (overload) { + auto o = overload.operator()(a0, a1); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CSimpleMap::serializeFrom(a0, a1); + } +}; + +void bind_mrpt_maps_CSimpleMap(std::function< pybind11::module &(std::string const &namespace_) > &M) +{ + { // mrpt::maps::CSimpleMap file:mrpt/maps/CSimpleMap.h line:57 + pybind11::class_, PyCallBack_mrpt_maps_CSimpleMap, mrpt::serialization::CSerializable> cl(M("mrpt::maps"), "CSimpleMap", "A view-based map: a set of poses and what the robot saw from those poses.\n\n A simplemap comprises a sequence of tuples, each containing:\n - The **keyframe SE(3) pose** of the robot, including (optionally) its\n uncertainty, as instances of mrpt::poses::CPose3DPDF\n - The **raw observations** from that keyframe, in a mrpt::obs::CSensoryFrame\n - Optionally, the **twist** (linear and angular velocity) of the robot in the\n local frame of reference, at that moment. It can be used to undistort data\n from a rotatory lidar, for example.\n\n To generate an actual metric map (occupancy grid, point cloud, octomap, etc.)\n from a \"simple map\", the user must instantiate the desired metric map\n class(es) and invoke its virtual method\n mrpt::maps::CMetricMap::loadFromSimpleMap().\n\n Users can also use the new top-level [library\n mp2p_icp_filters](https://github.com/MOLAorg/mp2p_icp/) and its CLI\n application\n [sm2mm](https://github.com/MOLAorg/mp2p_icp/tree/master/apps/sm2mm)\n (simple-map to metric-map)\n to generate metric maps including pre-processing of raw data in a flexible\n way.\n\n To programatically change an existing simplemap, use the non-const get()\n method and modify the returned reference.\n\n \n Objects of this class are serialized into GZ-compressed files with\n the extension `.simplemap`.\n See [Robotics file formats](robotics_file_formats.html).\n\n \n mrpt::obs::CSensoryFrame, mrpt::poses::CPose3DPDF,\n mrpt::maps::CMetricMap, https://github.com/MOLAorg/mp2p_icp/\n\n \n\n "); + cl.def( pybind11::init( [](){ return new mrpt::maps::CSimpleMap(); }, [](){ return new PyCallBack_mrpt_maps_CSimpleMap(); } ) ); + cl.def( pybind11::init( [](PyCallBack_mrpt_maps_CSimpleMap const &o){ return new PyCallBack_mrpt_maps_CSimpleMap(o); } ) ); + cl.def( pybind11::init( [](mrpt::maps::CSimpleMap const &o){ return new mrpt::maps::CSimpleMap(o); } ) ); + cl.def_static("GetRuntimeClassIdStatic", (const struct mrpt::rtti::TRuntimeClassId & (*)()) &mrpt::maps::CSimpleMap::GetRuntimeClassIdStatic, "C++: mrpt::maps::CSimpleMap::GetRuntimeClassIdStatic() --> const struct mrpt::rtti::TRuntimeClassId &", pybind11::return_value_policy::automatic); + cl.def("GetRuntimeClass", (const struct mrpt::rtti::TRuntimeClassId * (mrpt::maps::CSimpleMap::*)() const) &mrpt::maps::CSimpleMap::GetRuntimeClass, "C++: mrpt::maps::CSimpleMap::GetRuntimeClass() const --> const struct mrpt::rtti::TRuntimeClassId *", pybind11::return_value_policy::automatic); + cl.def("clone", (class mrpt::rtti::CObject * (mrpt::maps::CSimpleMap::*)() const) &mrpt::maps::CSimpleMap::clone, "C++: mrpt::maps::CSimpleMap::clone() const --> class mrpt::rtti::CObject *", pybind11::return_value_policy::automatic); + cl.def_static("CreateObject", (class std::shared_ptr (*)()) &mrpt::maps::CSimpleMap::CreateObject, "C++: mrpt::maps::CSimpleMap::CreateObject() --> class std::shared_ptr"); + cl.def("assign", (class mrpt::maps::CSimpleMap & (mrpt::maps::CSimpleMap::*)(const class mrpt::maps::CSimpleMap &)) &mrpt::maps::CSimpleMap::operator=, "Copy, making a deep copy of all data. \n\nC++: mrpt::maps::CSimpleMap::operator=(const class mrpt::maps::CSimpleMap &) --> class mrpt::maps::CSimpleMap &", pybind11::return_value_policy::automatic, pybind11::arg("o")); + cl.def("saveToFile", (bool (mrpt::maps::CSimpleMap::*)(const std::string &) const) &mrpt::maps::CSimpleMap::saveToFile, "Save this object to a .simplemap binary file (compressed with gzip)\n See [Robotics file formats](robotics_file_formats.html).\n \n\n loadFromFile()\n \n\n false on any error. \n\nC++: mrpt::maps::CSimpleMap::saveToFile(const std::string &) const --> bool", pybind11::arg("filName")); + cl.def("loadFromFile", (bool (mrpt::maps::CSimpleMap::*)(const std::string &)) &mrpt::maps::CSimpleMap::loadFromFile, "Load the contents of this object from a .simplemap binary file (possibly\n compressed with gzip)\n See [Robotics file formats](robotics_file_formats.html).\n \n\n saveToFile()\n \n\n false on any error. \n\nC++: mrpt::maps::CSimpleMap::loadFromFile(const std::string &) --> bool", pybind11::arg("filName")); + cl.def("size", (size_t (mrpt::maps::CSimpleMap::*)() const) &mrpt::maps::CSimpleMap::size, "Returns the number of keyframes in the map \n\nC++: mrpt::maps::CSimpleMap::size() const --> size_t"); + cl.def("empty", (bool (mrpt::maps::CSimpleMap::*)() const) &mrpt::maps::CSimpleMap::empty, "Returns size()!=0 \n\nC++: mrpt::maps::CSimpleMap::empty() const --> bool"); + cl.def("get", (struct mrpt::maps::CSimpleMap::Keyframe & (mrpt::maps::CSimpleMap::*)(size_t)) &mrpt::maps::CSimpleMap::get, "non-const accessor, returning a reference suitable for modification\n\nC++: mrpt::maps::CSimpleMap::get(size_t) --> struct mrpt::maps::CSimpleMap::Keyframe &", pybind11::return_value_policy::automatic, pybind11::arg("index")); + cl.def("remove", (void (mrpt::maps::CSimpleMap::*)(size_t)) &mrpt::maps::CSimpleMap::remove, "Deletes the 0-based index i'th keyframe.\n \n\n std::exception On index out of bounds.\n \n\n insert, get, set\n\nC++: mrpt::maps::CSimpleMap::remove(size_t) --> void", pybind11::arg("index")); + cl.def("insert", (void (mrpt::maps::CSimpleMap::*)(const struct mrpt::maps::CSimpleMap::Keyframe &)) &mrpt::maps::CSimpleMap::insert, "Adds a new keyframe (SE(3) pose) to the view-based map.\n Both shared pointers are copied (shallow object copies).\n\nC++: mrpt::maps::CSimpleMap::insert(const struct mrpt::maps::CSimpleMap::Keyframe &) --> void", pybind11::arg("kf")); + cl.def("clear", (void (mrpt::maps::CSimpleMap::*)()) &mrpt::maps::CSimpleMap::clear, "Remove all stored keyframes. \n remove \n\nC++: mrpt::maps::CSimpleMap::clear() --> void"); + cl.def("changeCoordinatesOrigin", (void (mrpt::maps::CSimpleMap::*)(const class mrpt::poses::CPose3D &)) &mrpt::maps::CSimpleMap::changeCoordinatesOrigin, "Change the coordinate origin of all stored poses, that is, translates\n and rotates the map such that the old SE(3) origin (identity\n transformation) becomes the new provided one.\n\nC++: mrpt::maps::CSimpleMap::changeCoordinatesOrigin(const class mrpt::poses::CPose3D &) --> void", pybind11::arg("newOrigin")); + + { // mrpt::maps::CSimpleMap::Keyframe file:mrpt/maps/CSimpleMap.h line:70 + auto & enclosing_class = cl; + pybind11::class_> cl(enclosing_class, "Keyframe", ""); + cl.def( pybind11::init( [](){ return new mrpt::maps::CSimpleMap::Keyframe(); } ) ); + cl.def( pybind11::init( [](mrpt::maps::CSimpleMap::Keyframe const &o){ return new mrpt::maps::CSimpleMap::Keyframe(o); } ) ); + cl.def_readwrite("pose", &mrpt::maps::CSimpleMap::Keyframe::pose); + cl.def_readwrite("sf", &mrpt::maps::CSimpleMap::Keyframe::sf); + cl.def_readwrite("localTwist", &mrpt::maps::CSimpleMap::Keyframe::localTwist); + cl.def("assign", (struct mrpt::maps::CSimpleMap::Keyframe & (mrpt::maps::CSimpleMap::Keyframe::*)(const struct mrpt::maps::CSimpleMap::Keyframe &)) &mrpt::maps::CSimpleMap::Keyframe::operator=, "C++: mrpt::maps::CSimpleMap::Keyframe::operator=(const struct mrpt::maps::CSimpleMap::Keyframe &) --> struct mrpt::maps::CSimpleMap::Keyframe &", pybind11::return_value_policy::automatic, pybind11::arg("")); + } + + } +} diff --git a/python/src/mrpt/maps/CVoxelMap.cpp b/python/src/mrpt/maps/CVoxelMap.cpp index 6955a6caf6..e8bc80b5d8 100644 --- a/python/src/mrpt/maps/CVoxelMap.cpp +++ b/python/src/mrpt/maps/CVoxelMap.cpp @@ -36,6 +36,7 @@ #include #include #include +#include #include #include #include @@ -71,7 +72,6 @@ #include #include #include -#include #include #include #include diff --git a/python/src/mrpt/maps/CVoxelMapBase.cpp b/python/src/mrpt/maps/CVoxelMapBase.cpp index 64a11658b0..8d31660086 100644 --- a/python/src/mrpt/maps/CVoxelMapBase.cpp +++ b/python/src/mrpt/maps/CVoxelMapBase.cpp @@ -52,8 +52,7 @@ void bind_mrpt_maps_CVoxelMapBase(std::function< pybind11::module &(std::string cl.def("clear", (void (mrpt::maps::CMetricMap::*)()) &mrpt::maps::CMetricMap::clear, "Erase all the contents of the map \n\nC++: mrpt::maps::CMetricMap::clear() --> void"); cl.def("isEmpty", (bool (mrpt::maps::CMetricMap::*)() const) &mrpt::maps::CMetricMap::isEmpty, "Returns true if the map is empty/no observation has been inserted.\n\nC++: mrpt::maps::CMetricMap::isEmpty() const --> bool"); cl.def("boundingBox", (struct mrpt::math::TBoundingBox_ (mrpt::maps::CMetricMap::*)() const) &mrpt::maps::CMetricMap::boundingBox, "Returns the bounding box of the metric map, or (0,0,0)-(0,0,0) (the\n default value of mrpt::math::TBoundingBoxf() if not implemented in the\n derived class or the map is empty.\n\nC++: mrpt::maps::CMetricMap::boundingBox() const --> struct mrpt::math::TBoundingBox_"); - cl.def("loadFromProbabilisticPosesAndObservations", (void (mrpt::maps::CMetricMap::*)(const class mrpt::maps::CSimpleMap &)) &mrpt::maps::CMetricMap::loadFromProbabilisticPosesAndObservations, "Load the map contents from a CSimpleMap object, erasing all previous\n content of the map. This is done invoking `insertObservation()` for each\n observation at the mean 3D robot pose of each pose-observations pair in\n the CSimpleMap object.\n\n \n insertObservation, CSimpleMap\n \n\n std::exception Some internal steps in invoked methods can\n raise exceptions on invalid parameters, etc...\n\nC++: mrpt::maps::CMetricMap::loadFromProbabilisticPosesAndObservations(const class mrpt::maps::CSimpleMap &) --> void", pybind11::arg("Map")); - cl.def("loadFromSimpleMap", (void (mrpt::maps::CMetricMap::*)(const class mrpt::maps::CSimpleMap &)) &mrpt::maps::CMetricMap::loadFromSimpleMap, "! \n\nC++: mrpt::maps::CMetricMap::loadFromSimpleMap(const class mrpt::maps::CSimpleMap &) --> void", pybind11::arg("Map")); + cl.def("loadFromSimpleMap", (void (mrpt::maps::CMetricMap::*)(const class mrpt::maps::CSimpleMap &)) &mrpt::maps::CMetricMap::loadFromSimpleMap, "Load the map contents from a CSimpleMap object, erasing all previous\n content of the map. This is done invoking `insertObservation()` for each\n observation at the mean 3D robot pose of each pose-observations pair in\n the CSimpleMap object.\n\n \n insertObservation, CSimpleMap\n \n\n std::exception Some internal steps in invoked methods can\n raise exceptions on invalid parameters, etc...\n\nC++: mrpt::maps::CMetricMap::loadFromSimpleMap(const class mrpt::maps::CSimpleMap &) --> void", pybind11::arg("Map")); cl.def("insertObs", [](mrpt::maps::CMetricMap &o, const class mrpt::obs::CObservation & a0) -> bool { return o.insertObs(a0); }, "", pybind11::arg("obs")); cl.def("insertObs", (bool (mrpt::maps::CMetricMap::*)(const class mrpt::obs::CObservation &, const class mrpt::poses::CPose3D *)) &mrpt::maps::CMetricMap::insertObs, "C++: mrpt::maps::CMetricMap::insertObs(const class mrpt::obs::CObservation &, const class mrpt::poses::CPose3D *) --> bool", pybind11::arg("obs"), pybind11::arg("robotPose")); cl.def("insertObs", [](mrpt::maps::CMetricMap &o, const class mrpt::obs::CSensoryFrame & a0) -> bool { return o.insertObs(a0); }, "", pybind11::arg("sf")); @@ -84,8 +83,7 @@ void bind_mrpt_maps_CVoxelMapBase(std::function< pybind11::module &(std::string cl.def("clear", (void (mrpt::maps::CMetricMap::*)()) &mrpt::maps::CMetricMap::clear, "Erase all the contents of the map \n\nC++: mrpt::maps::CMetricMap::clear() --> void"); cl.def("isEmpty", (bool (mrpt::maps::CMetricMap::*)() const) &mrpt::maps::CMetricMap::isEmpty, "Returns true if the map is empty/no observation has been inserted.\n\nC++: mrpt::maps::CMetricMap::isEmpty() const --> bool"); cl.def("boundingBox", (struct mrpt::math::TBoundingBox_ (mrpt::maps::CMetricMap::*)() const) &mrpt::maps::CMetricMap::boundingBox, "Returns the bounding box of the metric map, or (0,0,0)-(0,0,0) (the\n default value of mrpt::math::TBoundingBoxf() if not implemented in the\n derived class or the map is empty.\n\nC++: mrpt::maps::CMetricMap::boundingBox() const --> struct mrpt::math::TBoundingBox_"); - cl.def("loadFromProbabilisticPosesAndObservations", (void (mrpt::maps::CMetricMap::*)(const class mrpt::maps::CSimpleMap &)) &mrpt::maps::CMetricMap::loadFromProbabilisticPosesAndObservations, "Load the map contents from a CSimpleMap object, erasing all previous\n content of the map. This is done invoking `insertObservation()` for each\n observation at the mean 3D robot pose of each pose-observations pair in\n the CSimpleMap object.\n\n \n insertObservation, CSimpleMap\n \n\n std::exception Some internal steps in invoked methods can\n raise exceptions on invalid parameters, etc...\n\nC++: mrpt::maps::CMetricMap::loadFromProbabilisticPosesAndObservations(const class mrpt::maps::CSimpleMap &) --> void", pybind11::arg("Map")); - cl.def("loadFromSimpleMap", (void (mrpt::maps::CMetricMap::*)(const class mrpt::maps::CSimpleMap &)) &mrpt::maps::CMetricMap::loadFromSimpleMap, "! \n\nC++: mrpt::maps::CMetricMap::loadFromSimpleMap(const class mrpt::maps::CSimpleMap &) --> void", pybind11::arg("Map")); + cl.def("loadFromSimpleMap", (void (mrpt::maps::CMetricMap::*)(const class mrpt::maps::CSimpleMap &)) &mrpt::maps::CMetricMap::loadFromSimpleMap, "Load the map contents from a CSimpleMap object, erasing all previous\n content of the map. This is done invoking `insertObservation()` for each\n observation at the mean 3D robot pose of each pose-observations pair in\n the CSimpleMap object.\n\n \n insertObservation, CSimpleMap\n \n\n std::exception Some internal steps in invoked methods can\n raise exceptions on invalid parameters, etc...\n\nC++: mrpt::maps::CMetricMap::loadFromSimpleMap(const class mrpt::maps::CSimpleMap &) --> void", pybind11::arg("Map")); cl.def("insertObs", [](mrpt::maps::CMetricMap &o, const class mrpt::obs::CObservation & a0) -> bool { return o.insertObs(a0); }, "", pybind11::arg("obs")); cl.def("insertObs", (bool (mrpt::maps::CMetricMap::*)(const class mrpt::obs::CObservation &, const class mrpt::poses::CPose3D *)) &mrpt::maps::CMetricMap::insertObs, "C++: mrpt::maps::CMetricMap::insertObs(const class mrpt::obs::CObservation &, const class mrpt::poses::CPose3D *) --> bool", pybind11::arg("obs"), pybind11::arg("robotPose")); cl.def("insertObs", [](mrpt::maps::CMetricMap &o, const class mrpt::obs::CSensoryFrame & a0) -> bool { return o.insertObs(a0); }, "", pybind11::arg("sf")); diff --git a/python/src/mrpt/maps/CVoxelMapOccupancyBase_1.cpp b/python/src/mrpt/maps/CVoxelMapOccupancyBase_1.cpp index 7fbf0e079e..6cd258ca20 100644 --- a/python/src/mrpt/maps/CVoxelMapOccupancyBase_1.cpp +++ b/python/src/mrpt/maps/CVoxelMapOccupancyBase_1.cpp @@ -85,8 +85,7 @@ void bind_mrpt_maps_CVoxelMapOccupancyBase_1(std::function< pybind11::module &(s cl.def("clear", (void (mrpt::maps::CMetricMap::*)()) &mrpt::maps::CMetricMap::clear, "Erase all the contents of the map \n\nC++: mrpt::maps::CMetricMap::clear() --> void"); cl.def("isEmpty", (bool (mrpt::maps::CMetricMap::*)() const) &mrpt::maps::CMetricMap::isEmpty, "Returns true if the map is empty/no observation has been inserted.\n\nC++: mrpt::maps::CMetricMap::isEmpty() const --> bool"); cl.def("boundingBox", (struct mrpt::math::TBoundingBox_ (mrpt::maps::CMetricMap::*)() const) &mrpt::maps::CMetricMap::boundingBox, "Returns the bounding box of the metric map, or (0,0,0)-(0,0,0) (the\n default value of mrpt::math::TBoundingBoxf() if not implemented in the\n derived class or the map is empty.\n\nC++: mrpt::maps::CMetricMap::boundingBox() const --> struct mrpt::math::TBoundingBox_"); - cl.def("loadFromProbabilisticPosesAndObservations", (void (mrpt::maps::CMetricMap::*)(const class mrpt::maps::CSimpleMap &)) &mrpt::maps::CMetricMap::loadFromProbabilisticPosesAndObservations, "Load the map contents from a CSimpleMap object, erasing all previous\n content of the map. This is done invoking `insertObservation()` for each\n observation at the mean 3D robot pose of each pose-observations pair in\n the CSimpleMap object.\n\n \n insertObservation, CSimpleMap\n \n\n std::exception Some internal steps in invoked methods can\n raise exceptions on invalid parameters, etc...\n\nC++: mrpt::maps::CMetricMap::loadFromProbabilisticPosesAndObservations(const class mrpt::maps::CSimpleMap &) --> void", pybind11::arg("Map")); - cl.def("loadFromSimpleMap", (void (mrpt::maps::CMetricMap::*)(const class mrpt::maps::CSimpleMap &)) &mrpt::maps::CMetricMap::loadFromSimpleMap, "! \n\nC++: mrpt::maps::CMetricMap::loadFromSimpleMap(const class mrpt::maps::CSimpleMap &) --> void", pybind11::arg("Map")); + cl.def("loadFromSimpleMap", (void (mrpt::maps::CMetricMap::*)(const class mrpt::maps::CSimpleMap &)) &mrpt::maps::CMetricMap::loadFromSimpleMap, "Load the map contents from a CSimpleMap object, erasing all previous\n content of the map. This is done invoking `insertObservation()` for each\n observation at the mean 3D robot pose of each pose-observations pair in\n the CSimpleMap object.\n\n \n insertObservation, CSimpleMap\n \n\n std::exception Some internal steps in invoked methods can\n raise exceptions on invalid parameters, etc...\n\nC++: mrpt::maps::CMetricMap::loadFromSimpleMap(const class mrpt::maps::CSimpleMap &) --> void", pybind11::arg("Map")); cl.def("insertObs", [](mrpt::maps::CMetricMap &o, const class mrpt::obs::CObservation & a0) -> bool { return o.insertObs(a0); }, "", pybind11::arg("obs")); cl.def("insertObs", (bool (mrpt::maps::CMetricMap::*)(const class mrpt::obs::CObservation &, const class mrpt::poses::CPose3D *)) &mrpt::maps::CMetricMap::insertObs, "C++: mrpt::maps::CMetricMap::insertObs(const class mrpt::obs::CObservation &, const class mrpt::poses::CPose3D *) --> bool", pybind11::arg("obs"), pybind11::arg("robotPose")); cl.def("insertObs", [](mrpt::maps::CMetricMap &o, const class mrpt::obs::CSensoryFrame & a0) -> bool { return o.insertObs(a0); }, "", pybind11::arg("sf")); diff --git a/python/src/mrpt/maps/CVoxelMapOccupancyBase_2.cpp b/python/src/mrpt/maps/CVoxelMapOccupancyBase_2.cpp index d24835a7dd..f76785b4a5 100644 --- a/python/src/mrpt/maps/CVoxelMapOccupancyBase_2.cpp +++ b/python/src/mrpt/maps/CVoxelMapOccupancyBase_2.cpp @@ -85,8 +85,7 @@ void bind_mrpt_maps_CVoxelMapOccupancyBase_2(std::function< pybind11::module &(s cl.def("clear", (void (mrpt::maps::CMetricMap::*)()) &mrpt::maps::CMetricMap::clear, "Erase all the contents of the map \n\nC++: mrpt::maps::CMetricMap::clear() --> void"); cl.def("isEmpty", (bool (mrpt::maps::CMetricMap::*)() const) &mrpt::maps::CMetricMap::isEmpty, "Returns true if the map is empty/no observation has been inserted.\n\nC++: mrpt::maps::CMetricMap::isEmpty() const --> bool"); cl.def("boundingBox", (struct mrpt::math::TBoundingBox_ (mrpt::maps::CMetricMap::*)() const) &mrpt::maps::CMetricMap::boundingBox, "Returns the bounding box of the metric map, or (0,0,0)-(0,0,0) (the\n default value of mrpt::math::TBoundingBoxf() if not implemented in the\n derived class or the map is empty.\n\nC++: mrpt::maps::CMetricMap::boundingBox() const --> struct mrpt::math::TBoundingBox_"); - cl.def("loadFromProbabilisticPosesAndObservations", (void (mrpt::maps::CMetricMap::*)(const class mrpt::maps::CSimpleMap &)) &mrpt::maps::CMetricMap::loadFromProbabilisticPosesAndObservations, "Load the map contents from a CSimpleMap object, erasing all previous\n content of the map. This is done invoking `insertObservation()` for each\n observation at the mean 3D robot pose of each pose-observations pair in\n the CSimpleMap object.\n\n \n insertObservation, CSimpleMap\n \n\n std::exception Some internal steps in invoked methods can\n raise exceptions on invalid parameters, etc...\n\nC++: mrpt::maps::CMetricMap::loadFromProbabilisticPosesAndObservations(const class mrpt::maps::CSimpleMap &) --> void", pybind11::arg("Map")); - cl.def("loadFromSimpleMap", (void (mrpt::maps::CMetricMap::*)(const class mrpt::maps::CSimpleMap &)) &mrpt::maps::CMetricMap::loadFromSimpleMap, "! \n\nC++: mrpt::maps::CMetricMap::loadFromSimpleMap(const class mrpt::maps::CSimpleMap &) --> void", pybind11::arg("Map")); + cl.def("loadFromSimpleMap", (void (mrpt::maps::CMetricMap::*)(const class mrpt::maps::CSimpleMap &)) &mrpt::maps::CMetricMap::loadFromSimpleMap, "Load the map contents from a CSimpleMap object, erasing all previous\n content of the map. This is done invoking `insertObservation()` for each\n observation at the mean 3D robot pose of each pose-observations pair in\n the CSimpleMap object.\n\n \n insertObservation, CSimpleMap\n \n\n std::exception Some internal steps in invoked methods can\n raise exceptions on invalid parameters, etc...\n\nC++: mrpt::maps::CMetricMap::loadFromSimpleMap(const class mrpt::maps::CSimpleMap &) --> void", pybind11::arg("Map")); cl.def("insertObs", [](mrpt::maps::CMetricMap &o, const class mrpt::obs::CObservation & a0) -> bool { return o.insertObs(a0); }, "", pybind11::arg("obs")); cl.def("insertObs", (bool (mrpt::maps::CMetricMap::*)(const class mrpt::obs::CObservation &, const class mrpt::poses::CPose3D *)) &mrpt::maps::CMetricMap::insertObs, "C++: mrpt::maps::CMetricMap::insertObs(const class mrpt::obs::CObservation &, const class mrpt::poses::CPose3D *) --> bool", pybind11::arg("obs"), pybind11::arg("robotPose")); cl.def("insertObs", [](mrpt::maps::CMetricMap &o, const class mrpt::obs::CSensoryFrame & a0) -> bool { return o.insertObs(a0); }, "", pybind11::arg("sf")); diff --git a/python/src/mrpt/maps/CWirelessPowerGridMap2D.cpp b/python/src/mrpt/maps/CWirelessPowerGridMap2D.cpp index 0f9d9bbd61..498de30614 100644 --- a/python/src/mrpt/maps/CWirelessPowerGridMap2D.cpp +++ b/python/src/mrpt/maps/CWirelessPowerGridMap2D.cpp @@ -39,6 +39,7 @@ #include #include #include +#include #include #include #include @@ -73,7 +74,6 @@ #include #include #include -#include #include #include #include diff --git a/python/src/mrpt/math/TTwist3D.cpp b/python/src/mrpt/math/TTwist3D.cpp index 174b12b147..714012d67b 100644 --- a/python/src/mrpt/math/TTwist3D.cpp +++ b/python/src/mrpt/math/TTwist3D.cpp @@ -49,5 +49,6 @@ void bind_mrpt_math_TTwist3D(std::function< pybind11::module &(std::string const cl.def("rotated", (struct mrpt::math::TTwist3D (mrpt::math::TTwist3D::*)(const struct mrpt::math::TPose3D &) const) &mrpt::math::TTwist3D::rotated, "Like rotate(), but returning a copy of the rotated twist.\n \n\n New in MRPT 2.3.2 \n\nC++: mrpt::math::TTwist3D::rotated(const struct mrpt::math::TPose3D &) const --> struct mrpt::math::TTwist3D", pybind11::arg("rot")); cl.def("fromString", (void (mrpt::math::TTwist3D::*)(const std::string &)) &mrpt::math::TTwist3D::fromString, "Set the current object value from a string generated by 'asString' (eg:\n \"[vx vy vz wx wy wz]\" )\n \n\n asString\n \n\n std::exception On invalid format\n\nC++: mrpt::math::TTwist3D::fromString(const std::string &) --> void", pybind11::arg("s")); cl.def_static("FromString", (struct mrpt::math::TTwist3D (*)(const std::string &)) &mrpt::math::TTwist3D::FromString, "C++: mrpt::math::TTwist3D::FromString(const std::string &) --> struct mrpt::math::TTwist3D", pybind11::arg("s")); + cl.def("assign", (struct mrpt::math::TTwist3D & (mrpt::math::TTwist3D::*)(const struct mrpt::math::TTwist3D &)) &mrpt::math::TTwist3D::operator=, "C++: mrpt::math::TTwist3D::operator=(const struct mrpt::math::TTwist3D &) --> struct mrpt::math::TTwist3D &", pybind11::return_value_policy::automatic, pybind11::arg("")); } } diff --git a/python/src/mrpt/slam/CIncrementalMapPartitioner.cpp b/python/src/mrpt/slam/CIncrementalMapPartitioner.cpp index b9e3f23bf1..768ded4af8 100644 --- a/python/src/mrpt/slam/CIncrementalMapPartitioner.cpp +++ b/python/src/mrpt/slam/CIncrementalMapPartitioner.cpp @@ -14,6 +14,7 @@ #include #include #include +#include #include #include #include @@ -36,7 +37,6 @@ #include #include // __str__ #include -#include #include #include #include diff --git a/python/src/mrpt/slam/CMetricMapBuilder.cpp b/python/src/mrpt/slam/CMetricMapBuilder.cpp index 0e0a1e67dc..62f0e656f1 100644 --- a/python/src/mrpt/slam/CMetricMapBuilder.cpp +++ b/python/src/mrpt/slam/CMetricMapBuilder.cpp @@ -24,6 +24,7 @@ #include #include #include +#include #include #include #include diff --git a/python/src/mrpt/slam/CMetricMapBuilderICP.cpp b/python/src/mrpt/slam/CMetricMapBuilderICP.cpp index 5e8ce1ba60..3e5c11fe0f 100644 --- a/python/src/mrpt/slam/CMetricMapBuilderICP.cpp +++ b/python/src/mrpt/slam/CMetricMapBuilderICP.cpp @@ -31,6 +31,7 @@ #include #include #include +#include #include #include #include diff --git a/python/src/pymrpt.cpp b/python/src/pymrpt.cpp index 9bc222edb2..b0dd90f7db 100644 --- a/python/src/pymrpt.cpp +++ b/python/src/pymrpt.cpp @@ -106,6 +106,8 @@ void bind_mrpt_apps_MonteCarloLocalization_App(std::function< pybind11::module & void bind_mrpt_img_TColor(std::function< pybind11::module &(std::string const &namespace_) > &M); void bind_mrpt_img_CCanvas(std::function< pybind11::module &(std::string const &namespace_) > &M); void bind_mrpt_maps_CMultiMetricMap(std::function< pybind11::module &(std::string const &namespace_) > &M); +void bind_mrpt_math_TTwist3D(std::function< pybind11::module &(std::string const &namespace_) > &M); +void bind_mrpt_maps_CSimpleMap(std::function< pybind11::module &(std::string const &namespace_) > &M); void bind_mrpt_bayes_CProbabilityParticle(std::function< pybind11::module &(std::string const &namespace_) > &M); void bind_mrpt_bayes_CParticleFilterData(std::function< pybind11::module &(std::string const &namespace_) > &M); void bind_mrpt_bayes_CParticleFilterData_1(std::function< pybind11::module &(std::string const &namespace_) > &M); @@ -288,7 +290,6 @@ void bind_mrpt_opengl_CSetOfTriangles(std::function< pybind11::module &(std::str void bind_mrpt_opengl_CPlanarLaserScan(std::function< pybind11::module &(std::string const &namespace_) > &M); void bind_mrpt_math_CAtan2LookUpTable(std::function< pybind11::module &(std::string const &namespace_) > &M); void bind_mrpt_math_ops_containers(std::function< pybind11::module &(std::string const &namespace_) > &M); -void bind_mrpt_math_TTwist3D(std::function< pybind11::module &(std::string const &namespace_) > &M); void bind_mrpt_math_data_utils(std::function< pybind11::module &(std::string const &namespace_) > &M); void bind_mrpt_math_fresnel(std::function< pybind11::module &(std::string const &namespace_) > &M); void bind_mrpt_nav_holonomic_ClearanceDiagram(std::function< pybind11::module &(std::string const &namespace_) > &M); @@ -536,6 +537,8 @@ PYBIND11_MODULE(pymrpt, root_module) { bind_mrpt_img_TColor(M); bind_mrpt_img_CCanvas(M); bind_mrpt_maps_CMultiMetricMap(M); + bind_mrpt_math_TTwist3D(M); + bind_mrpt_maps_CSimpleMap(M); bind_mrpt_bayes_CProbabilityParticle(M); bind_mrpt_bayes_CParticleFilterData(M); bind_mrpt_bayes_CParticleFilterData_1(M); @@ -718,7 +721,6 @@ PYBIND11_MODULE(pymrpt, root_module) { bind_mrpt_opengl_CPlanarLaserScan(M); bind_mrpt_math_CAtan2LookUpTable(M); bind_mrpt_math_ops_containers(M); - bind_mrpt_math_TTwist3D(M); bind_mrpt_math_data_utils(M); bind_mrpt_math_fresnel(M); bind_mrpt_nav_holonomic_ClearanceDiagram(M); diff --git a/python/src/pymrpt.sources b/python/src/pymrpt.sources index 5015a1f833..d182f5c286 100644 --- a/python/src/pymrpt.sources +++ b/python/src/pymrpt.sources @@ -96,6 +96,8 @@ mrpt/apps/MonteCarloLocalization_App.cpp mrpt/img/TColor.cpp mrpt/img/CCanvas.cpp mrpt/maps/CMultiMetricMap.cpp +mrpt/math/TTwist3D.cpp +mrpt/maps/CSimpleMap.cpp mrpt/bayes/CProbabilityParticle.cpp mrpt/bayes/CParticleFilterData.cpp mrpt/bayes/CParticleFilterData_1.cpp @@ -278,7 +280,6 @@ mrpt/opengl/CSetOfTriangles.cpp mrpt/opengl/CPlanarLaserScan.cpp mrpt/math/CAtan2LookUpTable.cpp mrpt/math/ops_containers.cpp -mrpt/math/TTwist3D.cpp mrpt/math/data_utils.cpp mrpt/math/fresnel.cpp mrpt/nav/holonomic/ClearanceDiagram.cpp diff --git a/python/src/unknown/unknown_6.cpp b/python/src/unknown/unknown_6.cpp index 4a99579891..05fb332486 100644 --- a/python/src/unknown/unknown_6.cpp +++ b/python/src/unknown/unknown_6.cpp @@ -115,7 +115,7 @@ struct PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_GENERIC_SHORT_FRAME : public mrp } }; -// mrpt::obs::gnss::Message_NV_OEM6_BESTPOS file: line:82 +// mrpt::obs::gnss::Message_NV_OEM6_BESTPOS file: line:86 struct PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_BESTPOS : public mrpt::obs::gnss::Message_NV_OEM6_BESTPOS { using mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::Message_NV_OEM6_BESTPOS; @@ -160,7 +160,7 @@ struct PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_BESTPOS : public mrpt::obs::gnss } }; -// mrpt::obs::gnss::Message_NV_OEM6_INSPVAS file: line:88 +// mrpt::obs::gnss::Message_NV_OEM6_INSPVAS file: line:92 struct PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_INSPVAS : public mrpt::obs::gnss::Message_NV_OEM6_INSPVAS { using mrpt::obs::gnss::Message_NV_OEM6_INSPVAS::Message_NV_OEM6_INSPVAS; @@ -205,7 +205,7 @@ struct PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_INSPVAS : public mrpt::obs::gnss } }; -// mrpt::obs::gnss::Message_NV_OEM6_INSCOVS file: line:94 +// mrpt::obs::gnss::Message_NV_OEM6_INSCOVS file: line:98 struct PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_INSCOVS : public mrpt::obs::gnss::Message_NV_OEM6_INSCOVS { using mrpt::obs::gnss::Message_NV_OEM6_INSCOVS::Message_NV_OEM6_INSCOVS; @@ -317,7 +317,7 @@ void bind_unknown_unknown_6(std::function< pybind11::module &(std::string const cl.def("fixEndianness", (void (mrpt::obs::gnss::Message_NV_OEM6_GENERIC_SHORT_FRAME::*)()) &mrpt::obs::gnss::Message_NV_OEM6_GENERIC_SHORT_FRAME::fixEndianness, "C++: mrpt::obs::gnss::Message_NV_OEM6_GENERIC_SHORT_FRAME::fixEndianness() --> void"); cl.def("assign", (struct mrpt::obs::gnss::Message_NV_OEM6_GENERIC_SHORT_FRAME & (mrpt::obs::gnss::Message_NV_OEM6_GENERIC_SHORT_FRAME::*)(const struct mrpt::obs::gnss::Message_NV_OEM6_GENERIC_SHORT_FRAME &)) &mrpt::obs::gnss::Message_NV_OEM6_GENERIC_SHORT_FRAME::operator=, "C++: mrpt::obs::gnss::Message_NV_OEM6_GENERIC_SHORT_FRAME::operator=(const struct mrpt::obs::gnss::Message_NV_OEM6_GENERIC_SHORT_FRAME &) --> struct mrpt::obs::gnss::Message_NV_OEM6_GENERIC_SHORT_FRAME &", pybind11::return_value_policy::automatic, pybind11::arg("")); } - { // mrpt::obs::gnss::Message_NV_OEM6_BESTPOS file: line:82 + { // mrpt::obs::gnss::Message_NV_OEM6_BESTPOS file: line:86 pybind11::class_, PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_BESTPOS, mrpt::obs::gnss::gnss_message> cl(M("mrpt::obs::gnss"), "Message_NV_OEM6_BESTPOS", ""); cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::Message_NV_OEM6_BESTPOS(); }, [](){ return new PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_BESTPOS(); } ) ); cl.def( pybind11::init( [](PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_BESTPOS const &o){ return new PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_BESTPOS(o); } ) ); @@ -357,7 +357,7 @@ void bind_unknown_unknown_6(std::function< pybind11::module &(std::string const } } - { // mrpt::obs::gnss::Message_NV_OEM6_INSPVAS file: line:88 + { // mrpt::obs::gnss::Message_NV_OEM6_INSPVAS file: line:92 pybind11::class_, PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_INSPVAS, mrpt::obs::gnss::gnss_message> cl(M("mrpt::obs::gnss"), "Message_NV_OEM6_INSPVAS", ""); cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::Message_NV_OEM6_INSPVAS(); }, [](){ return new PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_INSPVAS(); } ) ); cl.def( pybind11::init( [](PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_INSPVAS const &o){ return new PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_INSPVAS(o); } ) ); @@ -389,7 +389,7 @@ void bind_unknown_unknown_6(std::function< pybind11::module &(std::string const } } - { // mrpt::obs::gnss::Message_NV_OEM6_INSCOVS file: line:94 + { // mrpt::obs::gnss::Message_NV_OEM6_INSCOVS file: line:98 pybind11::class_, PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_INSCOVS, mrpt::obs::gnss::gnss_message> cl(M("mrpt::obs::gnss"), "Message_NV_OEM6_INSCOVS", ""); cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::Message_NV_OEM6_INSCOVS(); }, [](){ return new PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_INSCOVS(); } ) ); cl.def( pybind11::init( [](PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_INSCOVS const &o){ return new PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_INSCOVS(o); } ) ); diff --git a/python/src/unknown/unknown_7.cpp b/python/src/unknown/unknown_7.cpp index 6955b09b24..8cbcc882ef 100644 --- a/python/src/unknown/unknown_7.cpp +++ b/python/src/unknown/unknown_7.cpp @@ -25,7 +25,7 @@ PYBIND11_MAKE_OPAQUE(std::shared_ptr) #endif -// mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS file: line:100 +// mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS file: line:104 struct PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_RXSTATUS : public mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS { using mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS::Message_NV_OEM6_RXSTATUS; @@ -70,7 +70,7 @@ struct PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_RXSTATUS : public mrpt::obs::gns } }; -// mrpt::obs::gnss::Message_NV_OEM6_RAWEPHEM file: line:106 +// mrpt::obs::gnss::Message_NV_OEM6_RAWEPHEM file: line:110 struct PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_RAWEPHEM : public mrpt::obs::gnss::Message_NV_OEM6_RAWEPHEM { using mrpt::obs::gnss::Message_NV_OEM6_RAWEPHEM::Message_NV_OEM6_RAWEPHEM; @@ -160,7 +160,7 @@ struct PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_VERSION : public mrpt::obs::gnss } }; -// mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS file: line:112 +// mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS file: line:116 struct PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_RAWIMUS : public mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS { using mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS::Message_NV_OEM6_RAWIMUS; @@ -205,7 +205,7 @@ struct PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_RAWIMUS : public mrpt::obs::gnss } }; -// mrpt::obs::gnss::Message_NV_OEM6_MARKPOS file: line:118 +// mrpt::obs::gnss::Message_NV_OEM6_MARKPOS file: line:122 struct PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_MARKPOS : public mrpt::obs::gnss::Message_NV_OEM6_MARKPOS { using mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::Message_NV_OEM6_MARKPOS; @@ -252,7 +252,7 @@ struct PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_MARKPOS : public mrpt::obs::gnss void bind_unknown_unknown_7(std::function< pybind11::module &(std::string const &namespace_) > &M) { - { // mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS file: line:100 + { // mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS file: line:104 pybind11::class_, PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_RXSTATUS, mrpt::obs::gnss::gnss_message> cl(M("mrpt::obs::gnss"), "Message_NV_OEM6_RXSTATUS", ""); cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS(); }, [](){ return new PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_RXSTATUS(); } ) ); cl.def( pybind11::init( [](PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_RXSTATUS const &o){ return new PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_RXSTATUS(o); } ) ); @@ -290,7 +290,7 @@ void bind_unknown_unknown_7(std::function< pybind11::module &(std::string const } } - { // mrpt::obs::gnss::Message_NV_OEM6_RAWEPHEM file: line:106 + { // mrpt::obs::gnss::Message_NV_OEM6_RAWEPHEM file: line:110 pybind11::class_, PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_RAWEPHEM, mrpt::obs::gnss::gnss_message> cl(M("mrpt::obs::gnss"), "Message_NV_OEM6_RAWEPHEM", ""); cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::Message_NV_OEM6_RAWEPHEM(); }, [](){ return new PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_RAWEPHEM(); } ) ); cl.def( pybind11::init( [](PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_RAWEPHEM const &o){ return new PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_RAWEPHEM(o); } ) ); @@ -333,7 +333,7 @@ void bind_unknown_unknown_7(std::function< pybind11::module &(std::string const } } - { // mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS file: line:112 + { // mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS file: line:116 pybind11::class_, PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_RAWIMUS, mrpt::obs::gnss::gnss_message> cl(M("mrpt::obs::gnss"), "Message_NV_OEM6_RAWIMUS", ""); cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS(); }, [](){ return new PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_RAWIMUS(); } ) ); cl.def( pybind11::init( [](PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_RAWIMUS const &o){ return new PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_RAWIMUS(o); } ) ); @@ -362,7 +362,7 @@ void bind_unknown_unknown_7(std::function< pybind11::module &(std::string const } } - { // mrpt::obs::gnss::Message_NV_OEM6_MARKPOS file: line:118 + { // mrpt::obs::gnss::Message_NV_OEM6_MARKPOS file: line:122 pybind11::class_, PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_MARKPOS, mrpt::obs::gnss::gnss_message> cl(M("mrpt::obs::gnss"), "Message_NV_OEM6_MARKPOS", ""); cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::Message_NV_OEM6_MARKPOS(); }, [](){ return new PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_MARKPOS(); } ) ); cl.def( pybind11::init( [](PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_MARKPOS const &o){ return new PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_MARKPOS(o); } ) ); diff --git a/python/src/unknown/unknown_8.cpp b/python/src/unknown/unknown_8.cpp index ac4aaccbb1..a475ccb6c0 100644 --- a/python/src/unknown/unknown_8.cpp +++ b/python/src/unknown/unknown_8.cpp @@ -25,7 +25,7 @@ PYBIND11_MAKE_OPAQUE(std::shared_ptr) #endif -// mrpt::obs::gnss::Message_NV_OEM6_MARKTIME file: line:124 +// mrpt::obs::gnss::Message_NV_OEM6_MARKTIME file: line:128 struct PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_MARKTIME : public mrpt::obs::gnss::Message_NV_OEM6_MARKTIME { using mrpt::obs::gnss::Message_NV_OEM6_MARKTIME::Message_NV_OEM6_MARKTIME; @@ -70,7 +70,7 @@ struct PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_MARKTIME : public mrpt::obs::gns } }; -// mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME file: line:130 +// mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME file: line:5 struct PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_MARK2TIME : public mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME { using mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME::Message_NV_OEM6_MARK2TIME; @@ -115,7 +115,7 @@ struct PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_MARK2TIME : public mrpt::obs::gn } }; -// mrpt::obs::gnss::Message_NV_OEM6_IONUTC file: line:6 +// mrpt::obs::gnss::Message_NV_OEM6_IONUTC file: line:11 struct PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_IONUTC : public mrpt::obs::gnss::Message_NV_OEM6_IONUTC { using mrpt::obs::gnss::Message_NV_OEM6_IONUTC::Message_NV_OEM6_IONUTC; @@ -252,7 +252,7 @@ struct PyCallBack_mrpt_obs_gnss_Message_TOPCON_SATS : public mrpt::obs::gnss::Me void bind_unknown_unknown_8(std::function< pybind11::module &(std::string const &namespace_) > &M) { - { // mrpt::obs::gnss::Message_NV_OEM6_MARKTIME file: line:124 + { // mrpt::obs::gnss::Message_NV_OEM6_MARKTIME file: line:128 pybind11::class_, PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_MARKTIME, mrpt::obs::gnss::gnss_message> cl(M("mrpt::obs::gnss"), "Message_NV_OEM6_MARKTIME", ""); cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::Message_NV_OEM6_MARKTIME(); }, [](){ return new PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_MARKTIME(); } ) ); cl.def( pybind11::init( [](PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_MARKTIME const &o){ return new PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_MARKTIME(o); } ) ); @@ -278,7 +278,7 @@ void bind_unknown_unknown_8(std::function< pybind11::module &(std::string const } } - { // mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME file: line:130 + { // mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME file: line:5 pybind11::class_, PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_MARK2TIME, mrpt::obs::gnss::gnss_message> cl(M("mrpt::obs::gnss"), "Message_NV_OEM6_MARK2TIME", ""); cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME(); }, [](){ return new PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_MARK2TIME(); } ) ); cl.def( pybind11::init( [](PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_MARK2TIME const &o){ return new PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_MARK2TIME(o); } ) ); @@ -304,7 +304,7 @@ void bind_unknown_unknown_8(std::function< pybind11::module &(std::string const } } - { // mrpt::obs::gnss::Message_NV_OEM6_IONUTC file: line:6 + { // mrpt::obs::gnss::Message_NV_OEM6_IONUTC file: line:11 pybind11::class_, PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_IONUTC, mrpt::obs::gnss::gnss_message> cl(M("mrpt::obs::gnss"), "Message_NV_OEM6_IONUTC", ""); cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::Message_NV_OEM6_IONUTC(); }, [](){ return new PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_IONUTC(); } ) ); cl.def( pybind11::init( [](PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_IONUTC const &o){ return new PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_IONUTC(o); } ) ); diff --git a/python/stubs-out/mrpt/pymrpt/mrpt/config.pyi b/python/stubs-out/mrpt/pymrpt/mrpt/config.pyi index 35155a8807..04359036f2 100644 --- a/python/stubs-out/mrpt/pymrpt/mrpt/config.pyi +++ b/python/stubs-out/mrpt/pymrpt/mrpt/config.pyi @@ -59,6 +59,7 @@ class CConfigFileBase: def getAllSections(classstd) -> void: ... def getContentAsYAML(self) -> str: ... def keyExists(self, section: str, key: str) -> bool: ... + def keys(self, section: str) -> List[str]: ... @overload def read_bool(self, section: str, name: str, defaultValue: bool) -> bool: ... @overload @@ -95,6 +96,7 @@ class CConfigFileBase: def sectionExists(self, section_name: str) -> bool: ... @overload def sectionExists(conststd) -> bool: ... + def sections(self) -> List[str]: ... @overload def setContentFromYAML(self, yaml_block: str) -> None: ... @overload diff --git a/python/stubs-out/mrpt/pymrpt/mrpt/maps.pyi b/python/stubs-out/mrpt/pymrpt/mrpt/maps.pyi index ae626cfbc6..05e8fe7254 100644 --- a/python/stubs-out/mrpt/pymrpt/mrpt/maps.pyi +++ b/python/stubs-out/mrpt/pymrpt/mrpt/maps.pyi @@ -1223,10 +1223,6 @@ class CMetricMap(mrpt.pymrpt.mrpt.serialization.CSerializable, mrpt.pymrpt.mrpt. @overload def isEmpty() -> bool: ... @overload - def loadFromProbabilisticPosesAndObservations(self, Map) -> None: ... - @overload - def loadFromProbabilisticPosesAndObservations(constclassmrpt) -> void: ... - @overload def loadFromSimpleMap(self, Map) -> None: ... @overload def loadFromSimpleMap(constclassmrpt) -> void: ... @@ -2372,10 +2368,6 @@ class COctoMapBase_octomap_ColorOcTree_octomap_ColorOcTreeNode_t(CMetricMap): @overload def isEmpty() -> bool: ... @overload - def loadFromProbabilisticPosesAndObservations(self, Map: CSimpleMap) -> None: ... - @overload - def loadFromProbabilisticPosesAndObservations(constclassmrpt) -> void: ... - @overload def loadFromSimpleMap(self, Map: CSimpleMap) -> None: ... @overload def loadFromSimpleMap(constclassmrpt) -> void: ... @@ -2632,10 +2624,6 @@ class COctoMapBase_octomap_OcTree_octomap_OcTreeNode_t(CMetricMap): @overload def isEmpty() -> bool: ... @overload - def loadFromProbabilisticPosesAndObservations(self, Map: CSimpleMap) -> None: ... - @overload - def loadFromProbabilisticPosesAndObservations(constclassmrpt) -> void: ... - @overload def loadFromSimpleMap(self, Map: CSimpleMap) -> None: ... @overload def loadFromSimpleMap(constclassmrpt) -> void: ... @@ -2935,11 +2923,19 @@ class CPointsMap(CMetricMap, mrpt.pymrpt.mrpt.opengl.PLY_Importer, mrpt.pymrpt.m def mark_as_modified(self) -> None: ... @overload def mark_as_modified() -> void: ... + @overload def nn_has_indices_or_ids(self) -> bool: ... @overload + def nn_has_indices_or_ids() -> bool: ... + @overload def nn_index_count(self) -> int: ... @overload def nn_index_count() -> size_t: ... + def nn_prepare_for_2d_queries(self) -> None: ... + @overload + def nn_prepare_for_3d_queries(self) -> None: ... + @overload + def nn_prepare_for_3d_queries() -> void: ... @overload def nn_single_search(self, query, result, out_dist_sqr: float, resultIndexOrID: int) -> bool: ... @overload @@ -3489,25 +3485,15 @@ class CReflectivityGridMap2D(CMetricMap, mrpt.pymrpt.mrpt.containers.CDynamicGri def saveMetricMapRepresentationToFile(conststd) -> void: ... class CSimpleMap(mrpt.pymrpt.mrpt.serialization.CSerializable): - class ConstPair: + class Keyframe: + localTwist: Optional[mrpt.pymrpt.mrpt.math.TTwist3D] pose: mrpt.pymrpt.mrpt.poses.CPose3DPDF sf: mrpt.pymrpt.mrpt.obs.CSensoryFrame @overload def __init__(self) -> None: ... @overload - def __init__(self, p: CSimpleMap.Pair) -> None: ... - @overload - def __init__(self, arg0: CSimpleMap.ConstPair) -> None: ... - def assign(self) -> CSimpleMap.ConstPair: ... - - class Pair: - pose: mrpt.pymrpt.mrpt.poses.CPose3DPDF - sf: mrpt.pymrpt.mrpt.obs.CSensoryFrame - @overload - def __init__(self) -> None: ... - @overload - def __init__(self, arg0: CSimpleMap.Pair) -> None: ... - def assign(self) -> CSimpleMap.Pair: ... + def __init__(self, arg0: CSimpleMap.Keyframe) -> None: ... + def assign(self) -> CSimpleMap.Keyframe: ... @overload def __init__(self) -> None: ... @overload @@ -3531,26 +3517,12 @@ class CSimpleMap(mrpt.pymrpt.mrpt.serialization.CSerializable): def empty(self) -> bool: ... @overload def empty() -> bool: ... + def get(self, *args, **kwargs) -> Any: ... @overload - def get(self, index: int, out_posePDF: mrpt.pymrpt.mrpt.poses.CPose3DPDF, out_SF: mrpt.pymrpt.mrpt.obs.CSensoryFrame) -> None: ... - @overload - def get(self, index: int, out_posePDF: mrpt.pymrpt.mrpt.poses.CPose3DPDF, out_SF: mrpt.pymrpt.mrpt.obs.CSensoryFrame) -> None: ... - @overload - def get(self, index: int) -> Tuple[mrpt.pymrpt.mrpt.poses.CPose3DPDF,mrpt.pymrpt.mrpt.obs.CSensoryFrame]: ... - def getAsPair(self, *args, **kwargs) -> Any: ... - @overload - def insert(self, in_posePDF: mrpt.pymrpt.mrpt.poses.CPose3DPDF, in_SF: mrpt.pymrpt.mrpt.obs.CSensoryFrame) -> None: ... - @overload - def insert(self, in_posePDF: mrpt.pymrpt.mrpt.poses.CPose3DPDF, in_SF: mrpt.pymrpt.mrpt.obs.CSensoryFrame) -> None: ... - @overload - def insert(self, poseSF) -> None: ... + def insert(self, kf) -> None: ... @overload def insert(conststructmrpt) -> void: ... @overload - def insert(self, in_posePDF: mrpt.pymrpt.mrpt.poses.CPosePDF, in_SF: mrpt.pymrpt.mrpt.obs.CSensoryFrame) -> None: ... - @overload - def insert(self, in_posePDF: mrpt.pymrpt.mrpt.poses.CPosePDF, in_SF: mrpt.pymrpt.mrpt.obs.CSensoryFrame) -> None: ... - @overload def loadFromFile(self, filName: str) -> bool: ... @overload def loadFromFile(conststd) -> bool: ... @@ -3562,7 +3534,6 @@ class CSimpleMap(mrpt.pymrpt.mrpt.serialization.CSerializable): def saveToFile(self, filName: str) -> bool: ... @overload def saveToFile(conststd) -> bool: ... - def set(self, *args, **kwargs) -> Any: ... @overload def size(self) -> int: ... @overload @@ -3702,10 +3673,6 @@ class CVoxelMapBase_mrpt_maps_VoxelNodeOccRGB_t(CMetricMap): @overload def isEmpty() -> bool: ... @overload - def loadFromProbabilisticPosesAndObservations(self, Map: CSimpleMap) -> None: ... - @overload - def loadFromProbabilisticPosesAndObservations(constclassmrpt) -> void: ... - @overload def loadFromSimpleMap(self, Map: CSimpleMap) -> None: ... @overload def loadFromSimpleMap(constclassmrpt) -> void: ... @@ -3773,10 +3740,6 @@ class CVoxelMapBase_mrpt_maps_VoxelNodeOccupancy_t(CMetricMap): @overload def isEmpty() -> bool: ... @overload - def loadFromProbabilisticPosesAndObservations(self, Map: CSimpleMap) -> None: ... - @overload - def loadFromProbabilisticPosesAndObservations(constclassmrpt) -> void: ... - @overload def loadFromSimpleMap(self, Map: CSimpleMap) -> None: ... @overload def loadFromSimpleMap(constclassmrpt) -> void: ... @@ -3867,10 +3830,6 @@ class CVoxelMapOccupancyBase_mrpt_maps_VoxelNodeOccRGB_signed_char_t(CVoxelMapBa def l2p(self, *args, **kwargs) -> Any: ... def l2p_255(self, *args, **kwargs) -> Any: ... @overload - def loadFromProbabilisticPosesAndObservations(self, Map: CSimpleMap) -> None: ... - @overload - def loadFromProbabilisticPosesAndObservations(constclassmrpt) -> void: ... - @overload def loadFromSimpleMap(self, Map: CSimpleMap) -> None: ... @overload def loadFromSimpleMap(constclassmrpt) -> void: ... @@ -3891,6 +3850,22 @@ class CVoxelMapOccupancyBase_mrpt_maps_VoxelNodeOccRGB_signed_char_t(CVoxelMapBa @overload def nn_index_count() -> size_t: ... @overload + def nn_prepare_for_2d_queries(self) -> None: ... + @overload + def nn_prepare_for_2d_queries() -> void: ... + @overload + def nn_prepare_for_2d_queries(self) -> None: ... + @overload + def nn_prepare_for_2d_queries() -> void: ... + @overload + def nn_prepare_for_3d_queries(self) -> None: ... + @overload + def nn_prepare_for_3d_queries() -> void: ... + @overload + def nn_prepare_for_3d_queries(self) -> None: ... + @overload + def nn_prepare_for_3d_queries() -> void: ... + @overload def nn_single_search(self, query, result, out_dist_sqr: float, resultIndexOrID: int) -> bool: ... @overload def nn_single_search(self, query, result, out_dist_sqr: float, resultIndexOrID: int) -> bool: ... @@ -3989,10 +3964,6 @@ class CVoxelMapOccupancyBase_mrpt_maps_VoxelNodeOccupancy_signed_char_t(CVoxelMa def l2p(self, *args, **kwargs) -> Any: ... def l2p_255(self, *args, **kwargs) -> Any: ... @overload - def loadFromProbabilisticPosesAndObservations(self, Map: CSimpleMap) -> None: ... - @overload - def loadFromProbabilisticPosesAndObservations(constclassmrpt) -> void: ... - @overload def loadFromSimpleMap(self, Map: CSimpleMap) -> None: ... @overload def loadFromSimpleMap(constclassmrpt) -> void: ... @@ -4013,6 +3984,22 @@ class CVoxelMapOccupancyBase_mrpt_maps_VoxelNodeOccupancy_signed_char_t(CVoxelMa @overload def nn_index_count() -> size_t: ... @overload + def nn_prepare_for_2d_queries(self) -> None: ... + @overload + def nn_prepare_for_2d_queries() -> void: ... + @overload + def nn_prepare_for_2d_queries(self) -> None: ... + @overload + def nn_prepare_for_2d_queries() -> void: ... + @overload + def nn_prepare_for_3d_queries(self) -> None: ... + @overload + def nn_prepare_for_3d_queries() -> void: ... + @overload + def nn_prepare_for_3d_queries(self) -> None: ... + @overload + def nn_prepare_for_3d_queries() -> void: ... + @overload def nn_single_search(self, query, result, out_dist_sqr: float, resultIndexOrID: int) -> bool: ... @overload def nn_single_search(self, query, result, out_dist_sqr: float, resultIndexOrID: int) -> bool: ... @@ -4113,7 +4100,7 @@ class CWeightedPointsMap(CPointsMap): @overload def setPointWeight(self, index: int, w: int) -> None: ... @overload - def setPointWeight(size_t, unsignedlong) -> void: ... + def setPointWeight(size_t, uint64_t) -> void: ... @overload def setSize(self, newLength: int) -> None: ... @overload @@ -4186,6 +4173,14 @@ class NearestNeighborsCapable: @overload def nn_index_count() -> size_t: ... @overload + def nn_prepare_for_2d_queries(self) -> None: ... + @overload + def nn_prepare_for_2d_queries() -> void: ... + @overload + def nn_prepare_for_3d_queries(self) -> None: ... + @overload + def nn_prepare_for_3d_queries() -> void: ... + @overload def nn_single_search(self, query, result, out_dist_sqr: float, resultIndexOrIDOrID: int) -> bool: ... @overload def nn_single_search(self, query, result, out_dist_sqr: float, resultIndexOrIDOrID: int) -> bool: ... diff --git a/python/stubs-out/mrpt/pymrpt/mrpt/math.pyi b/python/stubs-out/mrpt/pymrpt/mrpt/math.pyi index 84a8af62ce..a6f93ee69b 100644 --- a/python/stubs-out/mrpt/pymrpt/mrpt/math.pyi +++ b/python/stubs-out/mrpt/pymrpt/mrpt/math.pyi @@ -257,6 +257,49 @@ class CMatrixDynamic_float_t: def __getitem__(self, arg0: tuple) -> float: ... def __setitem__(self, arg0: tuple, arg1: float) -> None: ... +class CMatrixDynamic_mrpt_math_TPoint3D_float_t: + @overload + def __init__(self, arg0: CMatrixDynamic_mrpt_math_TPoint3D_float_t) -> None: ... + @overload + def __init__(self) -> None: ... + @overload + def __init__(self, row: int) -> None: ... + @overload + def __init__(self, row: int, col: int) -> None: ... + @overload + def __init__(self, m: CMatrixDynamic_mrpt_math_TPoint3D_float_t, cropRowCount: int, cropColCount: int) -> None: ... + @overload + def assign(self, m: CMatrixDynamic_mrpt_math_TPoint3D_float_t) -> CMatrixDynamic_mrpt_math_TPoint3D_float_t: ... + @overload + def assign(self, m: CMatrixDynamic_mrpt_math_TPoint3D_float_t) -> CMatrixDynamic_mrpt_math_TPoint3D_float_t: ... + @overload + def cols(self) -> int: ... + @overload + def cols() -> int: ... + def conservativeResize(self, row: int, col: int) -> None: ... + def data(self, *args, **kwargs) -> Any: ... + def derived(self) -> CMatrixDynamic_mrpt_math_TPoint3D_float_t: ... + @overload + def resize(self, row: int, col: int) -> None: ... + @overload + def resize(self, vectorLen: int) -> None: ... + @overload + def resize(size_t) -> void: ... + @overload + def rows(self) -> int: ... + @overload + def rows() -> int: ... + @overload + def setSize(self, row: int, col: int) -> None: ... + @overload + def setSize(self, row: int, col: int, zeroNewElements: bool) -> None: ... + @overload + def swap(self, o: CMatrixDynamic_mrpt_math_TPoint3D_float_t) -> None: ... + @overload + def swap(classmrpt) -> void: ... + def __call__(self, *args, **kwargs) -> Any: ... + def __getitem__(self, index) -> Any: ... + class CMatrixDynamic_unsigned_char_t: @overload def __init__(self, arg0: CMatrixDynamic_unsigned_char_t) -> None: ... @@ -1023,9 +1066,6 @@ class CMatrixFixed_float_3UL_1UL_t: def __call__(self, row: int, col: int) -> float: ... @overload def __call__(self, i: int) -> float: ... - @overload - def __getitem__(self, i: int) -> float: ... - @overload def __getitem__(self, arg0: tuple) -> float: ... def __setitem__(self, arg0: tuple, arg1: float) -> None: ... @@ -2844,6 +2884,7 @@ class TTwist3D: def asString(std) -> void: ... @overload def asString(self) -> str: ... + def assign(self) -> TTwist3D: ... @overload def fromString(self, s: str) -> None: ... @overload diff --git a/python/stubs-out/mrpt/pymrpt/mrpt/obs/__init__.pyi b/python/stubs-out/mrpt/pymrpt/mrpt/obs/__init__.pyi index b7931b987d..0529ea041f 100644 --- a/python/stubs-out/mrpt/pymrpt/mrpt/obs/__init__.pyi +++ b/python/stubs-out/mrpt/pymrpt/mrpt/obs/__init__.pyi @@ -1327,6 +1327,25 @@ class CObservationRobotPose(CObservation): def setSensorPose(constclassmrpt) -> void: ... class CObservationRotatingScan(CObservation): + class ExternalStorageFormat: + __doc__: ClassVar[str] = ... # read-only + __members__: ClassVar[dict] = ... # read-only + MRPT_Serialization: ClassVar[CObservationRotatingScan.ExternalStorageFormat] = ... + None: ClassVar[CObservationRotatingScan.ExternalStorageFormat] = ... + PlainTextFile: ClassVar[CObservationRotatingScan.ExternalStorageFormat] = ... + __entries: ClassVar[dict] = ... + def __init__(self, value: int) -> None: ... + def __eq__(self, other: object) -> bool: ... + def __getstate__(self) -> int: ... + def __hash__(self) -> int: ... + def __index__(self) -> int: ... + def __int__(self) -> int: ... + def __ne__(self, other: object) -> bool: ... + def __setstate__(self, state: int) -> None: ... + @property + def name(self) -> str: ... + @property + def value(self) -> int: ... azimuthSpan: float columnCount: int has_satellite_timestamp: bool @@ -1334,6 +1353,7 @@ class CObservationRotatingScan(CObservation): lidarModel: str maxRange: float minRange: float + organizedPoints: mrpt.pymrpt.mrpt.math.CMatrixDynamic_mrpt_math_TPoint3D_float_t originalReceivedTimestamp: mrpt.pymrpt.std.chrono.time_point_mrpt_Clock_std_chrono_duration_long_std_ratio_1_10000000_t rangeImage: mrpt.pymrpt.mrpt.math.CMatrixDynamic_unsigned_short_t rangeOtherLayers: Dict[str,mrpt.pymrpt.mrpt.math.CMatrixDynamic_unsigned_short_t] @@ -1358,23 +1378,39 @@ class CObservationRotatingScan(CObservation): @overload def fromGeneric(constclassmrpt) -> bool: ... @overload - def fromPointCloud(self, o: CObservationPointCloud) -> None: ... - @overload - def fromPointCloud(constclassmrpt) -> void: ... - @overload def fromScan2D(self, o: CObservation2DRangeScan) -> None: ... @overload def fromScan2D(constclassmrpt) -> void: ... def fromVelodyne(self, o: CObservationVelodyneScan) -> None: ... + def getExternalStorageFile(self) -> str: ... def getOriginalReceivedTimeStamp(self) -> mrpt.pymrpt.std.chrono.time_point_mrpt_Clock_std_chrono_duration_long_std_ratio_1_10000000_t: ... @overload def getSensorPose(self, out_sensorPose: mrpt.pymrpt.mrpt.poses.CPose3D) -> None: ... @overload def getSensorPose(classmrpt) -> void: ... + def isExternallyStored(self) -> bool: ... + def load(self) -> None: ... + @overload + def loadFromTextFile(self, filename: str) -> bool: ... + @overload + def loadFromTextFile(conststd) -> bool: ... + @overload + def overrideExternalStorageFormatFlag(self, fmt: CObservationRotatingScan.ExternalStorageFormat) -> None: ... + @overload + def overrideExternalStorageFormatFlag(constenummrpt) -> void: ... + def saveToTextFile(self, *args, **kwargs) -> Any: ... + @overload + def setAsExternalStorage(self, fileName: str, fmt: CObservationRotatingScan.ExternalStorageFormat) -> None: ... + @overload + def setAsExternalStorage(conststd, constenummrpt) -> void: ... @overload def setSensorPose(self, newSensorPose: mrpt.pymrpt.mrpt.poses.CPose3D) -> None: ... @overload def setSensorPose(constclassmrpt) -> void: ... + @overload + def unload(self) -> None: ... + @overload + def unload() -> void: ... class CObservationSkeleton(CObservation): class TSkeletonJoint: @@ -2156,6 +2192,10 @@ def obsPointCloud_to_viz(obs: CObservationPointCloud, p: VisualizationParameters @overload def obsPointCloud_to_viz(constclassstd, conststructmrpt, classmrpt) -> void: ... @overload +def obsRotatingScan_to_viz(obs: CObservationRotatingScan, p: VisualizationParameters, out: mrpt.pymrpt.mrpt.opengl.CSetOfObjects) -> None: ... +@overload +def obsRotatingScan_to_viz(constclassstd, conststructmrpt, classmrpt) -> void: ... +@overload def obsVelodyne_to_viz(obs: CObservationVelodyneScan, p: VisualizationParameters, out: mrpt.pymrpt.mrpt.opengl.CSetOfObjects) -> None: ... @overload def obsVelodyne_to_viz(constclassstd, conststructmrpt, classmrpt) -> void: ... diff --git a/python/stubs-out/mrpt/pymrpt/mrpt/opengl/__init__.pyi b/python/stubs-out/mrpt/pymrpt/mrpt/opengl/__init__.pyi index 5bc9a4c2dc..834566e71f 100644 --- a/python/stubs-out/mrpt/pymrpt/mrpt/opengl/__init__.pyi +++ b/python/stubs-out/mrpt/pymrpt/mrpt/opengl/__init__.pyi @@ -3932,6 +3932,10 @@ class Viewport(mrpt.pymrpt.mrpt.serialization.CSerializable, mrpt.pymrpt.mrpt.sy def getRenderMatrices(self) -> TRenderMatrices: ... def getViewportClipDistances(self, clip_min: float, clip_max: float) -> None: ... def getViewportPosition(self, *args, **kwargs) -> Any: ... + @overload + def getViewportVisibility(self) -> bool: ... + @overload + def getViewportVisibility() -> bool: ... def insert(self, *args, **kwargs) -> Any: ... @overload def isImageViewMode(self) -> bool: ... @@ -4001,7 +4005,9 @@ class Viewport(mrpt.pymrpt.mrpt.serialization.CSerializable, mrpt.pymrpt.mrpt.sy @overload def setImageView(self, img: mrpt.pymrpt.mrpt.img.CImage) -> None: ... @overload - def setImageView(constclassmrpt) -> void: ... + def setImageView(self, img: mrpt.pymrpt.mrpt.img.CImage, transparentBackground: bool) -> None: ... + @overload + def setImageView(constclassmrpt, bool) -> void: ... def setLightShadowClipDistances(self, clip_min: float, clip_max: float) -> None: ... @overload def setNormalMode(self) -> None: ... @@ -4014,6 +4020,10 @@ class Viewport(mrpt.pymrpt.mrpt.serialization.CSerializable, mrpt.pymrpt.mrpt.sy def setViewportClipDistances(self, clip_min: float, clip_max: float) -> None: ... def setViewportPosition(self, *args, **kwargs) -> Any: ... @overload + def setViewportVisibility(self, visible: bool) -> None: ... + @overload + def setViewportVisibility(bool) -> void: ... + @overload def size(self) -> int: ... @overload def size() -> size_t: ... diff --git a/python/stubs-out/mrpt/pymrpt/mrpt/poses/__init__.pyi b/python/stubs-out/mrpt/pymrpt/mrpt/poses/__init__.pyi index 001eab5d16..938120a808 100644 --- a/python/stubs-out/mrpt/pymrpt/mrpt/poses/__init__.pyi +++ b/python/stubs-out/mrpt/pymrpt/mrpt/poses/__init__.pyi @@ -1723,12 +1723,20 @@ class CPoseInterpolatorBase_2_t: def loadFromTextFile(self, s: str) -> bool: ... @overload def loadFromTextFile(conststd) -> bool: ... + @overload + def loadFromTextFile_TUM(self, s: str) -> bool: ... + @overload + def loadFromTextFile_TUM(conststd) -> bool: ... def saveInterpolatedToTextFile(self, s: str, period: mrpt.pymrpt.std.chrono.duration_long_std_ratio_1_10000000_t) -> bool: ... @overload def saveToTextFile(self, s: str) -> bool: ... @overload def saveToTextFile(conststd) -> bool: ... @overload + def saveToTextFile_TUM(self, s: str) -> bool: ... + @overload + def saveToTextFile_TUM(conststd) -> bool: ... + @overload def setInterpolationMethod(self, method: TInterpolatorMethod) -> None: ... @overload def setInterpolationMethod(enummrpt) -> void: ... @@ -1781,12 +1789,20 @@ class CPoseInterpolatorBase_3_t: def loadFromTextFile(self, s: str) -> bool: ... @overload def loadFromTextFile(conststd) -> bool: ... + @overload + def loadFromTextFile_TUM(self, s: str) -> bool: ... + @overload + def loadFromTextFile_TUM(conststd) -> bool: ... def saveInterpolatedToTextFile(self, s: str, period: mrpt.pymrpt.std.chrono.duration_long_std_ratio_1_10000000_t) -> bool: ... @overload def saveToTextFile(self, s: str) -> bool: ... @overload def saveToTextFile(conststd) -> bool: ... @overload + def saveToTextFile_TUM(self, s: str) -> bool: ... + @overload + def saveToTextFile_TUM(conststd) -> bool: ... + @overload def setInterpolationMethod(self, method: TInterpolatorMethod) -> None: ... @overload def setInterpolationMethod(enummrpt) -> void: ...