Skip to content

Commit

Permalink
Update python wrapper
Browse files Browse the repository at this point in the history
  • Loading branch information
jlblancoc committed Nov 29, 2023
1 parent 9fee6bf commit 5167955
Show file tree
Hide file tree
Showing 26 changed files with 402 additions and 186 deletions.
2 changes: 1 addition & 1 deletion python/generate-python.sh
Original file line number Diff line number Diff line change
Expand Up @@ -94,5 +94,5 @@ find $WRAP_OUT_DIR -name "*.cpp" | xargs -I FIL \

# applying manual patches:
echo "Applying manual patches to pybind11 code..."
find . -name "patch-0*.diff" | xargs -I FIL bash -c "echo \"Applying patch: FIL\" && git apply FIL --ignore-whitespace"
find . -name "patch-0*.diff" | sort | xargs -I FIL bash -c "echo \"Applying patch: FIL\" && git apply FIL --ignore-whitespace"

131 changes: 70 additions & 61 deletions python/patch-011.diff

Large diffs are not rendered by default.

112 changes: 0 additions & 112 deletions python/patch-012.diff

This file was deleted.

2 changes: 2 additions & 0 deletions python/src/mrpt/config/CConfigFileBase.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -180,7 +180,9 @@ void bind_mrpt_config_CConfigFileBase(std::function< pybind11::module &(std::str
cl.def("read_enum", [](mrpt::config::CConfigFileBase const &o, const std::string & a0, const std::string & a1, const enum mrpt::system::VerbosityLevel & a2) -> mrpt::system::VerbosityLevel { return o.read_enum(a0, a1, a2); }, "", pybind11::arg("section"), pybind11::arg("name"), pybind11::arg("defaultValue"));
cl.def("read_enum", (enum mrpt::system::VerbosityLevel (mrpt::config::CConfigFileBase::*)(const std::string &, const std::string &, const enum mrpt::system::VerbosityLevel &, bool) const) &mrpt::config::CConfigFileBase::read_enum<mrpt::system::VerbosityLevel>, "C++: mrpt::config::CConfigFileBase::read_enum(const std::string &, const std::string &, const enum mrpt::system::VerbosityLevel &, bool) const --> enum mrpt::system::VerbosityLevel", pybind11::arg("section"), pybind11::arg("name"), pybind11::arg("defaultValue"), pybind11::arg("failIfNotFound"));
cl.def("getAllSections", (void (mrpt::config::CConfigFileBase::*)(class std::vector<std::string > &) const) &mrpt::config::CConfigFileBase::getAllSections, "Returns a list with all the section names. \n\nC++: mrpt::config::CConfigFileBase::getAllSections(class std::vector<std::string > &) const --> void", pybind11::arg("sections"));
cl.def("sections", (class std::vector<std::string > (mrpt::config::CConfigFileBase::*)() const) &mrpt::config::CConfigFileBase::sections, "Returns, by value, a list with all the section names. \n\nC++: mrpt::config::CConfigFileBase::sections() const --> class std::vector<std::string >");
cl.def("getAllKeys", (void (mrpt::config::CConfigFileBase::*)(const std::string &, class std::vector<std::string > &) const) &mrpt::config::CConfigFileBase::getAllKeys, "Returs a list with all the keys into a section \n\nC++: mrpt::config::CConfigFileBase::getAllKeys(const std::string &, class std::vector<std::string > &) const --> void", pybind11::arg("section"), pybind11::arg("keys"));
cl.def("keys", (class std::vector<std::string > (mrpt::config::CConfigFileBase::*)(const std::string &) const) &mrpt::config::CConfigFileBase::keys, "Returs, by value, a list with all the keys into a section \n\nC++: mrpt::config::CConfigFileBase::keys(const std::string &) const --> class std::vector<std::string >", pybind11::arg("section"));
cl.def("sectionExists", (bool (mrpt::config::CConfigFileBase::*)(const std::string &) const) &mrpt::config::CConfigFileBase::sectionExists, "Checks if a given section exists (name is case insensitive)\n \n\n keyExists() \n\nC++: mrpt::config::CConfigFileBase::sectionExists(const std::string &) const --> bool", pybind11::arg("section_name"));
cl.def("keyExists", (bool (mrpt::config::CConfigFileBase::*)(const std::string &, const std::string &) const) &mrpt::config::CConfigFileBase::keyExists, "Checks if a given key exists inside a section (case insensitive)\n \n\n sectionExists() \n\nC++: mrpt::config::CConfigFileBase::keyExists(const std::string &, const std::string &) const --> bool", pybind11::arg("section"), pybind11::arg("key"));
cl.def("setContentFromYAML", (void (mrpt::config::CConfigFileBase::*)(const std::string &)) &mrpt::config::CConfigFileBase::setContentFromYAML, "Changes the contents of the virtual \"config file\" from a text block\n containing a YAML configuration text. Refer to unit test\n yaml2config_unittest.cpp for examples of use.\n \n\n getContentAsYAML()\n\nC++: mrpt::config::CConfigFileBase::setContentFromYAML(const std::string &) --> void", pybind11::arg("yaml_block"));
Expand Down
39 changes: 39 additions & 0 deletions python/src/mrpt/maps/CColouredOctoMap.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -830,6 +830,19 @@ struct PyCallBack_mrpt_maps_CColouredPointsMap : public mrpt::maps::CColouredPoi
}
return CColouredPointsMap::PLY_import_set_vertex_count(a0);
}
void PLY_import_set_vertex_timestamp(size_t a0, const double a1) override {
pybind11::gil_scoped_acquire gil;
pybind11::function overload = pybind11::get_overload(static_cast<const mrpt::maps::CColouredPointsMap *>(this), "PLY_import_set_vertex_timestamp");
if (overload) {
auto o = overload.operator()<pybind11::return_value_policy::reference>(a0, a1);
if (pybind11::detail::cast_is_temporary_value_reference<void>::value) {
static pybind11::detail::override_caster_t<void> caster;
return pybind11::detail::cast_ref<void>(std::move(o), caster);
}
else return pybind11::detail::cast_safe<void>(std::move(o));
}
return CColouredPointsMap::PLY_import_set_vertex_timestamp(a0, a1);
}
void PLY_export_get_vertex(size_t a0, struct mrpt::math::TPoint3D_<float> & a1, bool & a2, struct mrpt::img::TColorf & a3) const override {
pybind11::gil_scoped_acquire gil;
pybind11::function overload = pybind11::get_overload(static_cast<const mrpt::maps::CColouredPointsMap *>(this), "PLY_export_get_vertex");
Expand Down Expand Up @@ -986,6 +999,32 @@ struct PyCallBack_mrpt_maps_CColouredPointsMap : public mrpt::maps::CColouredPoi
}
return CPointsMap::asString();
}
void nn_prepare_for_2d_queries() const override {
pybind11::gil_scoped_acquire gil;
pybind11::function overload = pybind11::get_overload(static_cast<const mrpt::maps::CColouredPointsMap *>(this), "nn_prepare_for_2d_queries");
if (overload) {
auto o = overload.operator()<pybind11::return_value_policy::reference>();
if (pybind11::detail::cast_is_temporary_value_reference<void>::value) {
static pybind11::detail::override_caster_t<void> caster;
return pybind11::detail::cast_ref<void>(std::move(o), caster);
}
else return pybind11::detail::cast_safe<void>(std::move(o));
}
return CPointsMap::nn_prepare_for_2d_queries();
}
void nn_prepare_for_3d_queries() const override {
pybind11::gil_scoped_acquire gil;
pybind11::function overload = pybind11::get_overload(static_cast<const mrpt::maps::CColouredPointsMap *>(this), "nn_prepare_for_3d_queries");
if (overload) {
auto o = overload.operator()<pybind11::return_value_policy::reference>();
if (pybind11::detail::cast_is_temporary_value_reference<void>::value) {
static pybind11::detail::override_caster_t<void> caster;
return pybind11::detail::cast_ref<void>(std::move(o), caster);
}
else return pybind11::detail::cast_safe<void>(std::move(o));
}
return CPointsMap::nn_prepare_for_3d_queries();
}
bool nn_has_indices_or_ids() const override {
pybind11::gil_scoped_acquire gil;
pybind11::function overload = pybind11::get_overload(static_cast<const mrpt::maps::CColouredPointsMap *>(this), "nn_has_indices_or_ids");
Expand Down
2 changes: 1 addition & 1 deletion python/src/mrpt/maps/CColouredPointsMap.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -32,7 +32,7 @@

void bind_mrpt_maps_CColouredPointsMap(std::function< pybind11::module &(std::string const &namespace_) > &M)
{
{ // mrpt::opengl::PointCloudAdapter file:mrpt/maps/CColouredPointsMap.h line:366
{ // mrpt::opengl::PointCloudAdapter file:mrpt/maps/CColouredPointsMap.h line:374
pybind11::class_<mrpt::opengl::PointCloudAdapter<mrpt::maps::CColouredPointsMap>, std::shared_ptr<mrpt::opengl::PointCloudAdapter<mrpt::maps::CColouredPointsMap>>> cl(M("mrpt::opengl"), "PointCloudAdapter_mrpt_maps_CColouredPointsMap_t", "Specialization\n mrpt::opengl::PointCloudAdapter<mrpt::maps::CColouredPointsMap> \n\n\n mrpt_adapters_grp ");
cl.def( pybind11::init<const class mrpt::maps::CColouredPointsMap &>(), pybind11::arg("obj") );

Expand Down
27 changes: 27 additions & 0 deletions python/src/mrpt/maps/COccupancyGridMap2D.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -27,6 +27,7 @@
#include <mrpt/maps/CPointsMap.h>
#include <mrpt/maps/CSimpleMap.h>
#include <mrpt/maps/CSimplePointsMap.h>
#include <mrpt/maps/NearestNeighborsCapable.h>
#include <mrpt/maps/TMetricMapInitializer.h>
#include <mrpt/maps/metric_map_types.h>
#include <mrpt/math/CMatrixDynamic.h>
Expand Down Expand Up @@ -387,6 +388,32 @@ struct PyCallBack_mrpt_maps_COccupancyGridMap2D : public mrpt::maps::COccupancyG
}
return CMetricMap::squareDistanceToClosestCorrespondence(a0, a1);
}
void nn_prepare_for_2d_queries() const override {
pybind11::gil_scoped_acquire gil;
pybind11::function overload = pybind11::get_overload(static_cast<const mrpt::maps::COccupancyGridMap2D *>(this), "nn_prepare_for_2d_queries");
if (overload) {
auto o = overload.operator()<pybind11::return_value_policy::reference>();
if (pybind11::detail::cast_is_temporary_value_reference<void>::value) {
static pybind11::detail::override_caster_t<void> caster;
return pybind11::detail::cast_ref<void>(std::move(o), caster);
}
else return pybind11::detail::cast_safe<void>(std::move(o));
}
return NearestNeighborsCapable::nn_prepare_for_2d_queries();
}
void nn_prepare_for_3d_queries() const override {
pybind11::gil_scoped_acquire gil;
pybind11::function overload = pybind11::get_overload(static_cast<const mrpt::maps::COccupancyGridMap2D *>(this), "nn_prepare_for_3d_queries");
if (overload) {
auto o = overload.operator()<pybind11::return_value_policy::reference>();
if (pybind11::detail::cast_is_temporary_value_reference<void>::value) {
static pybind11::detail::override_caster_t<void> caster;
return pybind11::detail::cast_ref<void>(std::move(o), caster);
}
else return pybind11::detail::cast_safe<void>(std::move(o));
}
return NearestNeighborsCapable::nn_prepare_for_3d_queries();
}
};

// mrpt::maps::COccupancyGridMap2D::TInsertionOptions file:mrpt/maps/COccupancyGridMap2D.h line:475
Expand Down
27 changes: 27 additions & 0 deletions python/src/mrpt/maps/COccupancyGridMap3D.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -22,6 +22,7 @@
#include <mrpt/maps/CPointsMap.h>
#include <mrpt/maps/CSimpleMap.h>
#include <mrpt/maps/CSimplePointsMap.h>
#include <mrpt/maps/NearestNeighborsCapable.h>
#include <mrpt/maps/TMetricMapInitializer.h>
#include <mrpt/maps/metric_map_types.h>
#include <mrpt/math/CMatrixDynamic.h>
Expand Down Expand Up @@ -380,6 +381,32 @@ struct PyCallBack_mrpt_maps_COccupancyGridMap3D : public mrpt::maps::COccupancyG
}
return CMetricMap::squareDistanceToClosestCorrespondence(a0, a1);
}
void nn_prepare_for_2d_queries() const override {
pybind11::gil_scoped_acquire gil;
pybind11::function overload = pybind11::get_overload(static_cast<const mrpt::maps::COccupancyGridMap3D *>(this), "nn_prepare_for_2d_queries");
if (overload) {
auto o = overload.operator()<pybind11::return_value_policy::reference>();
if (pybind11::detail::cast_is_temporary_value_reference<void>::value) {
static pybind11::detail::override_caster_t<void> caster;
return pybind11::detail::cast_ref<void>(std::move(o), caster);
}
else return pybind11::detail::cast_safe<void>(std::move(o));
}
return NearestNeighborsCapable::nn_prepare_for_2d_queries();
}
void nn_prepare_for_3d_queries() const override {
pybind11::gil_scoped_acquire gil;
pybind11::function overload = pybind11::get_overload(static_cast<const mrpt::maps::COccupancyGridMap3D *>(this), "nn_prepare_for_3d_queries");
if (overload) {
auto o = overload.operator()<pybind11::return_value_policy::reference>();
if (pybind11::detail::cast_is_temporary_value_reference<void>::value) {
static pybind11::detail::override_caster_t<void> caster;
return pybind11::detail::cast_ref<void>(std::move(o), caster);
}
else return pybind11::detail::cast_safe<void>(std::move(o));
}
return NearestNeighborsCapable::nn_prepare_for_3d_queries();
}
};

// mrpt::maps::COccupancyGridMap3D::TInsertionOptions file:mrpt/maps/COccupancyGridMap3D.h line:221
Expand Down
39 changes: 39 additions & 0 deletions python/src/mrpt/maps/COctoMap.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -783,6 +783,19 @@ struct PyCallBack_mrpt_maps_CSimplePointsMap : public mrpt::maps::CSimplePointsM
}
return CSimplePointsMap::PLY_import_set_vertex_count(a0);
}
void PLY_import_set_vertex_timestamp(size_t a0, const double a1) override {
pybind11::gil_scoped_acquire gil;
pybind11::function overload = pybind11::get_overload(static_cast<const mrpt::maps::CSimplePointsMap *>(this), "PLY_import_set_vertex_timestamp");
if (overload) {
auto o = overload.operator()<pybind11::return_value_policy::reference>(a0, a1);
if (pybind11::detail::cast_is_temporary_value_reference<void>::value) {
static pybind11::detail::override_caster_t<void> caster;
return pybind11::detail::cast_ref<void>(std::move(o), caster);
}
else return pybind11::detail::cast_safe<void>(std::move(o));
}
return CSimplePointsMap::PLY_import_set_vertex_timestamp(a0, a1);
}
float squareDistanceToClosestCorrespondence(float a0, float a1) const override {
pybind11::gil_scoped_acquire gil;
pybind11::function overload = pybind11::get_overload(static_cast<const mrpt::maps::CSimplePointsMap *>(this), "squareDistanceToClosestCorrespondence");
Expand Down Expand Up @@ -991,6 +1004,32 @@ struct PyCallBack_mrpt_maps_CSimplePointsMap : public mrpt::maps::CSimplePointsM
}
return CPointsMap::asString();
}
void nn_prepare_for_2d_queries() const override {
pybind11::gil_scoped_acquire gil;
pybind11::function overload = pybind11::get_overload(static_cast<const mrpt::maps::CSimplePointsMap *>(this), "nn_prepare_for_2d_queries");
if (overload) {
auto o = overload.operator()<pybind11::return_value_policy::reference>();
if (pybind11::detail::cast_is_temporary_value_reference<void>::value) {
static pybind11::detail::override_caster_t<void> caster;
return pybind11::detail::cast_ref<void>(std::move(o), caster);
}
else return pybind11::detail::cast_safe<void>(std::move(o));
}
return CPointsMap::nn_prepare_for_2d_queries();
}
void nn_prepare_for_3d_queries() const override {
pybind11::gil_scoped_acquire gil;
pybind11::function overload = pybind11::get_overload(static_cast<const mrpt::maps::CSimplePointsMap *>(this), "nn_prepare_for_3d_queries");
if (overload) {
auto o = overload.operator()<pybind11::return_value_policy::reference>();
if (pybind11::detail::cast_is_temporary_value_reference<void>::value) {
static pybind11::detail::override_caster_t<void> caster;
return pybind11::detail::cast_ref<void>(std::move(o), caster);
}
else return pybind11::detail::cast_safe<void>(std::move(o));
}
return CPointsMap::nn_prepare_for_3d_queries();
}
bool nn_has_indices_or_ids() const override {
pybind11::gil_scoped_acquire gil;
pybind11::function overload = pybind11::get_overload(static_cast<const mrpt::maps::CSimplePointsMap *>(this), "nn_has_indices_or_ids");
Expand Down
39 changes: 39 additions & 0 deletions python/src/mrpt/maps/CPointCloudFilterByDistance.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -399,6 +399,19 @@ struct PyCallBack_mrpt_maps_CPointsMapXYZI : public mrpt::maps::CPointsMapXYZI {
}
return CPointsMapXYZI::PLY_import_set_vertex_count(a0);
}
void PLY_import_set_vertex_timestamp(size_t a0, const double a1) override {
pybind11::gil_scoped_acquire gil;
pybind11::function overload = pybind11::get_overload(static_cast<const mrpt::maps::CPointsMapXYZI *>(this), "PLY_import_set_vertex_timestamp");
if (overload) {
auto o = overload.operator()<pybind11::return_value_policy::reference>(a0, a1);
if (pybind11::detail::cast_is_temporary_value_reference<void>::value) {
static pybind11::detail::override_caster_t<void> caster;
return pybind11::detail::cast_ref<void>(std::move(o), caster);
}
else return pybind11::detail::cast_safe<void>(std::move(o));
}
return CPointsMapXYZI::PLY_import_set_vertex_timestamp(a0, a1);
}
void PLY_export_get_vertex(size_t a0, struct mrpt::math::TPoint3D_<float> & a1, bool & a2, struct mrpt::img::TColorf & a3) const override {
pybind11::gil_scoped_acquire gil;
pybind11::function overload = pybind11::get_overload(static_cast<const mrpt::maps::CPointsMapXYZI *>(this), "PLY_export_get_vertex");
Expand Down Expand Up @@ -555,6 +568,32 @@ struct PyCallBack_mrpt_maps_CPointsMapXYZI : public mrpt::maps::CPointsMapXYZI {
}
return CPointsMap::asString();
}
void nn_prepare_for_2d_queries() const override {
pybind11::gil_scoped_acquire gil;
pybind11::function overload = pybind11::get_overload(static_cast<const mrpt::maps::CPointsMapXYZI *>(this), "nn_prepare_for_2d_queries");
if (overload) {
auto o = overload.operator()<pybind11::return_value_policy::reference>();
if (pybind11::detail::cast_is_temporary_value_reference<void>::value) {
static pybind11::detail::override_caster_t<void> caster;
return pybind11::detail::cast_ref<void>(std::move(o), caster);
}
else return pybind11::detail::cast_safe<void>(std::move(o));
}
return CPointsMap::nn_prepare_for_2d_queries();
}
void nn_prepare_for_3d_queries() const override {
pybind11::gil_scoped_acquire gil;
pybind11::function overload = pybind11::get_overload(static_cast<const mrpt::maps::CPointsMapXYZI *>(this), "nn_prepare_for_3d_queries");
if (overload) {
auto o = overload.operator()<pybind11::return_value_policy::reference>();
if (pybind11::detail::cast_is_temporary_value_reference<void>::value) {
static pybind11::detail::override_caster_t<void> caster;
return pybind11::detail::cast_ref<void>(std::move(o), caster);
}
else return pybind11::detail::cast_safe<void>(std::move(o));
}
return CPointsMap::nn_prepare_for_3d_queries();
}
bool nn_has_indices_or_ids() const override {
pybind11::gil_scoped_acquire gil;
pybind11::function overload = pybind11::get_overload(static_cast<const mrpt::maps::CPointsMapXYZI *>(this), "nn_has_indices_or_ids");
Expand Down
4 changes: 3 additions & 1 deletion python/src/mrpt/maps/CPointsMap.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -253,7 +253,9 @@ void bind_mrpt_maps_CPointsMap(std::function< pybind11::module &(std::string con
cl.def("kdtree_distance", (float (mrpt::maps::CPointsMap::*)(const float *, size_t, size_t) const) &mrpt::maps::CPointsMap::kdtree_distance, "Returns the distance between the vector \"p1[0:size-1]\" and the data\n point with index \"idx_p2\" stored in the class:\n\nC++: mrpt::maps::CPointsMap::kdtree_distance(const float *, size_t, size_t) const --> float", pybind11::arg("p1"), pybind11::arg("idx_p2"), pybind11::arg("size"));
cl.def("mark_as_modified", (void (mrpt::maps::CPointsMap::*)() const) &mrpt::maps::CPointsMap::mark_as_modified, "Users normally don't need to call this. Called by this class or children\n classes, set m_largestDistanceFromOriginIsUpdated=false, invalidates the\n kd-tree cache, and such. \n\nC++: mrpt::maps::CPointsMap::mark_as_modified() const --> void");
cl.def("asString", (std::string (mrpt::maps::CPointsMap::*)() const) &mrpt::maps::CPointsMap::asString, "Returns a short description of the map. \n\nC++: mrpt::maps::CPointsMap::asString() const --> std::string");
cl.def("nn_has_indices_or_ids", (bool (mrpt::maps::CPointsMap::*)() const) &mrpt::maps::CPointsMap::nn_has_indices_or_ids, " @{ \n\nC++: mrpt::maps::CPointsMap::nn_has_indices_or_ids() const --> bool");
cl.def("nn_prepare_for_2d_queries", (void (mrpt::maps::CPointsMap::*)() const) &mrpt::maps::CPointsMap::nn_prepare_for_2d_queries, " @{ \n\nC++: mrpt::maps::CPointsMap::nn_prepare_for_2d_queries() const --> void");
cl.def("nn_prepare_for_3d_queries", (void (mrpt::maps::CPointsMap::*)() const) &mrpt::maps::CPointsMap::nn_prepare_for_3d_queries, "C++: mrpt::maps::CPointsMap::nn_prepare_for_3d_queries() const --> void");
cl.def("nn_has_indices_or_ids", (bool (mrpt::maps::CPointsMap::*)() const) &mrpt::maps::CPointsMap::nn_has_indices_or_ids, "C++: mrpt::maps::CPointsMap::nn_has_indices_or_ids() const --> bool");
cl.def("nn_index_count", (size_t (mrpt::maps::CPointsMap::*)() const) &mrpt::maps::CPointsMap::nn_index_count, "C++: mrpt::maps::CPointsMap::nn_index_count() const --> size_t");
cl.def("nn_single_search", (bool (mrpt::maps::CPointsMap::*)(const struct mrpt::math::TPoint3D_<float> &, struct mrpt::math::TPoint3D_<float> &, float &, uint64_t &) const) &mrpt::maps::CPointsMap::nn_single_search, "C++: mrpt::maps::CPointsMap::nn_single_search(const struct mrpt::math::TPoint3D_<float> &, struct mrpt::math::TPoint3D_<float> &, float &, uint64_t &) const --> bool", pybind11::arg("query"), pybind11::arg("result"), pybind11::arg("out_dist_sqr"), pybind11::arg("resultIndexOrID"));
cl.def("nn_single_search", (bool (mrpt::maps::CPointsMap::*)(const struct mrpt::math::TPoint2D_<float> &, struct mrpt::math::TPoint2D_<float> &, float &, uint64_t &) const) &mrpt::maps::CPointsMap::nn_single_search, "C++: mrpt::maps::CPointsMap::nn_single_search(const struct mrpt::math::TPoint2D_<float> &, struct mrpt::math::TPoint2D_<float> &, float &, uint64_t &) const --> bool", pybind11::arg("query"), pybind11::arg("result"), pybind11::arg("out_dist_sqr"), pybind11::arg("resultIndexOrID"));
Expand Down
Loading

0 comments on commit 5167955

Please sign in to comment.