Skip to content

Commit

Permalink
Update inconsistent types
Browse files Browse the repository at this point in the history
  • Loading branch information
jlblancoc committed Jun 26, 2024
1 parent e2870ce commit 3f63b96
Show file tree
Hide file tree
Showing 10 changed files with 31 additions and 77 deletions.
2 changes: 1 addition & 1 deletion libs/maps/include/mrpt/maps/CPointsMap.h
Original file line number Diff line number Diff line change
Expand Up @@ -533,7 +533,7 @@ class CPointsMap :
/// Gets the point weight, which is ignored in all classes (defaults to 1)
/// but in those which actually store that field (Note: No checks are done
/// for out-of-bounds index). \sa setPointWeight
virtual unsigned int getPointWeight([[maybe_unused]] size_t index) const { return 1; }
virtual unsigned long getPointWeight([[maybe_unused]] size_t index) const { return 1; }

/** Provides a direct access to points buffer, or nullptr if there is no
* points in the map.
Expand Down
2 changes: 1 addition & 1 deletion libs/maps/include/mrpt/maps/CWeightedPointsMap.h
Original file line number Diff line number Diff line change
Expand Up @@ -119,7 +119,7 @@ class CWeightedPointsMap : public CPointsMap
/// Gets the point weight, which is ignored in all classes (defaults to 1)
/// but in those which actually store that field (Note: No checks are done
/// for out-of-bounds index). \sa setPointWeight
unsigned int getPointWeight(size_t index) const override { return pointWeight[index]; }
unsigned long getPointWeight(size_t index) const override { return pointWeight[index]; }

protected:
/** The points weights */
Expand Down
31 changes: 0 additions & 31 deletions python/patch-013.diff
Original file line number Diff line number Diff line change
Expand Up @@ -32,15 +32,6 @@ diff --git a/python/src/mrpt/maps/CPointsMap.cpp b/python/src/mrpt/maps/CPointsM
index 6f4e1c86d..769c2e52c 100644
--- a/python/src/mrpt/maps/CPointsMap.cpp
+++ b/python/src/mrpt/maps/CPointsMap.cpp
@@ -214,7 +214,7 @@ void bind_mrpt_maps_CPointsMap(std::function< pybind11::module &(std::string con
cl.def("setPoint", (void (mrpt::maps::CPointsMap::*)(size_t, const struct mrpt::math::TPoint3D_<double> &)) &mrpt::maps::CPointsMap::setPoint, "C++: mrpt::maps::CPointsMap::setPoint(size_t, const struct mrpt::math::TPoint3D_<double> &) --> void", pybind11::arg("index"), pybind11::arg("p"));
cl.def("setPoint", (void (mrpt::maps::CPointsMap::*)(size_t, float, float)) &mrpt::maps::CPointsMap::setPoint, "C++: mrpt::maps::CPointsMap::setPoint(size_t, float, float) --> void", pybind11::arg("index"), pybind11::arg("x"), pybind11::arg("y"));
cl.def("setPointRGB", (void (mrpt::maps::CPointsMap::*)(size_t, float, float, float, float, float, float)) &mrpt::maps::CPointsMap::setPointRGB, "overload (RGB data is ignored in classes without color information)\n\nC++: mrpt::maps::CPointsMap::setPointRGB(size_t, float, float, float, float, float, float) --> void", pybind11::arg("index"), pybind11::arg("x"), pybind11::arg("y"), pybind11::arg("z"), pybind11::arg("R"), pybind11::arg("G"), pybind11::arg("B"));
- cl.def("setPointWeight", (void (mrpt::maps::CPointsMap::*)(size_t, unsigned long)) &mrpt::maps::CPointsMap::setPointWeight, "Sets the point weight, which is ignored in all classes but those which\n actually store that field (Note: No checks are done for out-of-bounds\n index). \n\n getPointWeight\n\nC++: mrpt::maps::CPointsMap::setPointWeight(size_t, unsigned long) --> void", pybind11::arg("index"), pybind11::arg("w"));
+ cl.def("setPointWeight", (void (mrpt::maps::CPointsMap::*)(size_t, uint64_t)) &mrpt::maps::CPointsMap::setPointWeight, "Sets the point weight, which is ignored in all classes but those which\n actually store that field (Note: No checks are done for out-of-bounds\n index). \n\n getPointWeight\n\nC++: mrpt::maps::CPointsMap::setPointWeight(size_t, uint64_t) --> void", pybind11::arg("index"), pybind11::arg("w"));
cl.def("getPointWeight", (unsigned int (mrpt::maps::CPointsMap::*)(size_t) const) &mrpt::maps::CPointsMap::getPointWeight, "Gets the point weight, which is ignored in all classes (defaults to 1)\n but in those which actually store that field (Note: No checks are done\n for out-of-bounds index). \n\n setPointWeight\n\nC++: mrpt::maps::CPointsMap::getPointWeight(size_t) const --> unsigned int", pybind11::arg("index"));
cl.def("hasField_Intensity", (bool (mrpt::maps::CPointsMap::*)() const) &mrpt::maps::CPointsMap::hasField_Intensity, "C++: mrpt::maps::CPointsMap::hasField_Intensity() const --> bool");
cl.def("hasField_Ring", (bool (mrpt::maps::CPointsMap::*)() const) &mrpt::maps::CPointsMap::hasField_Ring, "C++: mrpt::maps::CPointsMap::hasField_Ring() const --> bool");
@@ -259,7 +259,7 @@ void bind_mrpt_maps_CPointsMap(std::function< pybind11::module &(std::string con
cl.def("setHeightFilterLevels", (void (mrpt::maps::CPointsMap::*)(const double, const double)) &mrpt::maps::CPointsMap::setHeightFilterLevels, "Set the min/max Z levels for points to be actually inserted in the map\n (only if was called before). \n\nC++: mrpt::maps::CPointsMap::setHeightFilterLevels(const double, const double) --> void", pybind11::arg("_z_min"), pybind11::arg("_z_max"));
cl.def("getHeightFilterLevels", (void (mrpt::maps::CPointsMap::*)(double &, double &) const) &mrpt::maps::CPointsMap::getHeightFilterLevels, "Get the min/max Z levels for points to be actually inserted in the map\n \n\n enableFilterByHeight, setHeightFilterLevels \n\nC++: mrpt::maps::CPointsMap::getHeightFilterLevels(double &, double &) const --> void", pybind11::arg("_z_min"), pybind11::arg("_z_max"));
Expand All @@ -50,25 +41,3 @@ index 6f4e1c86d..769c2e52c 100644
cl.def("kdtree_get_point_count", (size_t (mrpt::maps::CPointsMap::*)() const) &mrpt::maps::CPointsMap::kdtree_get_point_count, "Must return the number of data points\n\nC++: mrpt::maps::CPointsMap::kdtree_get_point_count() const --> size_t");
cl.def("kdtree_get_pt", (float (mrpt::maps::CPointsMap::*)(size_t, int) const) &mrpt::maps::CPointsMap::kdtree_get_pt, "Returns the dim'th component of the idx'th point in the class:\n\nC++: mrpt::maps::CPointsMap::kdtree_get_pt(size_t, int) const --> float", pybind11::arg("idx"), pybind11::arg("dim"));
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"));
diff --git a/python/src/mrpt/maps/CReflectivityGridMap2D.cpp b/python/src/mrpt/maps/CReflectivityGridMap2D.cpp
index c786c92ec..23fb62762 100644
--- a/python/src/mrpt/maps/CReflectivityGridMap2D.cpp
+++ b/python/src/mrpt/maps/CReflectivityGridMap2D.cpp
@@ -589,7 +589,7 @@ struct PyCallBack_mrpt_maps_CWeightedPointsMap : public mrpt::maps::CWeightedPoi
}
return CWeightedPointsMap::addFrom_classSpecific(a0, a1, a2);
}
- void setPointWeight(size_t a0, unsigned long a1) override {
+ void setPointWeight(size_t a0, uint64_t a1) override {
pybind11::gil_scoped_acquire gil;
pybind11::function overload = pybind11::get_overload(static_cast<const mrpt::maps::CWeightedPointsMap *>(this), "setPointWeight");
if (overload) {
@@ -1207,7 +1207,7 @@ void bind_mrpt_maps_CReflectivityGridMap2D(std::function< pybind11::module &(std
cl.def("setSize", (void (mrpt::maps::CWeightedPointsMap::*)(size_t)) &mrpt::maps::CWeightedPointsMap::setSize, "C++: mrpt::maps::CWeightedPointsMap::setSize(size_t) --> void", pybind11::arg("newLength"));
cl.def("insertPointFast", [](mrpt::maps::CWeightedPointsMap &o, float const & a0, float const & a1) -> void { return o.insertPointFast(a0, a1); }, "", pybind11::arg("x"), pybind11::arg("y"));
cl.def("insertPointFast", (void (mrpt::maps::CWeightedPointsMap::*)(float, float, float)) &mrpt::maps::CWeightedPointsMap::insertPointFast, "The virtual method for *without* calling\n mark_as_modified() \n\nC++: mrpt::maps::CWeightedPointsMap::insertPointFast(float, float, float) --> void", pybind11::arg("x"), pybind11::arg("y"), pybind11::arg("z"));
- cl.def("setPointWeight", (void (mrpt::maps::CWeightedPointsMap::*)(size_t, unsigned long)) &mrpt::maps::CWeightedPointsMap::setPointWeight, "Sets the point weight, which is ignored in all classes but those which\n actually store that field (Note: No checks are done for out-of-bounds\n index). \n\n getPointWeight\n\nC++: mrpt::maps::CWeightedPointsMap::setPointWeight(size_t, unsigned long) --> void", pybind11::arg("index"), pybind11::arg("w"));
+ cl.def("setPointWeight", (void (mrpt::maps::CWeightedPointsMap::*)(size_t, uint64_t)) &mrpt::maps::CWeightedPointsMap::setPointWeight, "Sets the point weight, which is ignored in all classes but those which\n actually store that field (Note: No checks are done for out-of-bounds\n index). \n\n getPointWeight\n\nC++: mrpt::maps::CWeightedPointsMap::setPointWeight(size_t, uint64_t) --> void", pybind11::arg("index"), pybind11::arg("w"));
cl.def("getPointWeight", (unsigned int (mrpt::maps::CWeightedPointsMap::*)(size_t) const) &mrpt::maps::CWeightedPointsMap::getPointWeight, "Gets the point weight, which is ignored in all classes (defaults to 1)\n but in those which actually store that field (Note: No checks are done\n for out-of-bounds index). \n\n setPointWeight\n\nC++: mrpt::maps::CWeightedPointsMap::getPointWeight(size_t) const --> unsigned int", pybind11::arg("index"));

{ // mrpt::maps::CWeightedPointsMap::TMapDefinitionBase file: line:74
15 changes: 0 additions & 15 deletions python/patch-015.diff

This file was deleted.

10 changes: 5 additions & 5 deletions python/src/mrpt/maps/CColouredOctoMap.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -920,16 +920,16 @@ struct PyCallBack_mrpt_maps_CColouredPointsMap : public mrpt::maps::CColouredPoi
}
return CPointsMap::setPointWeight(a0, a1);
}
unsigned int getPointWeight(size_t a0) const override {
unsigned long getPointWeight(size_t a0) const override {
pybind11::gil_scoped_acquire gil;
pybind11::function overload = pybind11::get_overload(static_cast<const mrpt::maps::CColouredPointsMap *>(this), "getPointWeight");
if (overload) {
auto o = overload.operator()<pybind11::return_value_policy::reference>(a0);
if (pybind11::detail::cast_is_temporary_value_reference<unsigned int>::value) {
static pybind11::detail::override_caster_t<unsigned int> caster;
return pybind11::detail::cast_ref<unsigned int>(std::move(o), caster);
if (pybind11::detail::cast_is_temporary_value_reference<unsigned long>::value) {
static pybind11::detail::override_caster_t<unsigned long> caster;
return pybind11::detail::cast_ref<unsigned long>(std::move(o), caster);
}
else return pybind11::detail::cast_safe<unsigned int>(std::move(o));
else return pybind11::detail::cast_safe<unsigned long>(std::move(o));
}
return CPointsMap::getPointWeight(a0);
}
Expand Down
10 changes: 5 additions & 5 deletions python/src/mrpt/maps/COctoMap.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -860,16 +860,16 @@ struct PyCallBack_mrpt_maps_CSimplePointsMap : public mrpt::maps::CSimplePointsM
}
return CPointsMap::setPointWeight(a0, a1);
}
unsigned int getPointWeight(size_t a0) const override {
unsigned long getPointWeight(size_t a0) const override {
pybind11::gil_scoped_acquire gil;
pybind11::function overload = pybind11::get_overload(static_cast<const mrpt::maps::CSimplePointsMap *>(this), "getPointWeight");
if (overload) {
auto o = overload.operator()<pybind11::return_value_policy::reference>(a0);
if (pybind11::detail::cast_is_temporary_value_reference<unsigned int>::value) {
static pybind11::detail::override_caster_t<unsigned int> caster;
return pybind11::detail::cast_ref<unsigned int>(std::move(o), caster);
if (pybind11::detail::cast_is_temporary_value_reference<unsigned long>::value) {
static pybind11::detail::override_caster_t<unsigned long> caster;
return pybind11::detail::cast_ref<unsigned long>(std::move(o), caster);
}
else return pybind11::detail::cast_safe<unsigned int>(std::move(o));
else return pybind11::detail::cast_safe<unsigned long>(std::move(o));
}
return CPointsMap::getPointWeight(a0);
}
Expand Down
10 changes: 5 additions & 5 deletions python/src/mrpt/maps/CPointCloudFilterByDistance.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -463,16 +463,16 @@ struct PyCallBack_mrpt_maps_CPointsMapXYZI : public mrpt::maps::CPointsMapXYZI {
}
return CPointsMap::setPointWeight(a0, a1);
}
unsigned int getPointWeight(size_t a0) const override {
unsigned long getPointWeight(size_t a0) const override {
pybind11::gil_scoped_acquire gil;
pybind11::function overload = pybind11::get_overload(static_cast<const mrpt::maps::CPointsMapXYZI *>(this), "getPointWeight");
if (overload) {
auto o = overload.operator()<pybind11::return_value_policy::reference>(a0);
if (pybind11::detail::cast_is_temporary_value_reference<unsigned int>::value) {
static pybind11::detail::override_caster_t<unsigned int> caster;
return pybind11::detail::cast_ref<unsigned int>(std::move(o), caster);
if (pybind11::detail::cast_is_temporary_value_reference<unsigned long>::value) {
static pybind11::detail::override_caster_t<unsigned long> caster;
return pybind11::detail::cast_ref<unsigned long>(std::move(o), caster);
}
else return pybind11::detail::cast_safe<unsigned int>(std::move(o));
else return pybind11::detail::cast_safe<unsigned long>(std::move(o));
}
return CPointsMap::getPointWeight(a0);
}
Expand Down
4 changes: 2 additions & 2 deletions python/src/mrpt/maps/CPointsMap.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -214,8 +214,8 @@ void bind_mrpt_maps_CPointsMap(std::function< pybind11::module &(std::string con
cl.def("setPoint", (void (mrpt::maps::CPointsMap::*)(size_t, const struct mrpt::math::TPoint3D_<double> &)) &mrpt::maps::CPointsMap::setPoint, "C++: mrpt::maps::CPointsMap::setPoint(size_t, const struct mrpt::math::TPoint3D_<double> &) --> void", pybind11::arg("index"), pybind11::arg("p"));
cl.def("setPoint", (void (mrpt::maps::CPointsMap::*)(size_t, float, float)) &mrpt::maps::CPointsMap::setPoint, "C++: mrpt::maps::CPointsMap::setPoint(size_t, float, float) --> void", pybind11::arg("index"), pybind11::arg("x"), pybind11::arg("y"));
cl.def("setPointRGB", (void (mrpt::maps::CPointsMap::*)(size_t, float, float, float, float, float, float)) &mrpt::maps::CPointsMap::setPointRGB, "overload (RGB data is ignored in classes without color information)\n\nC++: mrpt::maps::CPointsMap::setPointRGB(size_t, float, float, float, float, float, float) --> void", pybind11::arg("index"), pybind11::arg("x"), pybind11::arg("y"), pybind11::arg("z"), pybind11::arg("R"), pybind11::arg("G"), pybind11::arg("B"));
cl.def("setPointWeight", (void (mrpt::maps::CPointsMap::*)(size_t, uint64_t)) &mrpt::maps::CPointsMap::setPointWeight, "Sets the point weight, which is ignored in all classes but those which\n actually store that field (Note: No checks are done for out-of-bounds\n index). \n\n getPointWeight\n\nC++: mrpt::maps::CPointsMap::setPointWeight(size_t, uint64_t) --> void", pybind11::arg("index"), pybind11::arg("w"));
cl.def("getPointWeight", (unsigned int (mrpt::maps::CPointsMap::*)(size_t) const) &mrpt::maps::CPointsMap::getPointWeight, "Gets the point weight, which is ignored in all classes (defaults to 1)\n but in those which actually store that field (Note: No checks are done\n for out-of-bounds index). \n\n setPointWeight\n\nC++: mrpt::maps::CPointsMap::getPointWeight(size_t) const --> unsigned int", pybind11::arg("index"));
cl.def("setPointWeight", (void (mrpt::maps::CPointsMap::*)(size_t, unsigned long)) &mrpt::maps::CPointsMap::setPointWeight, "Sets the point weight, which is ignored in all classes but those which\n actually store that field (Note: No checks are done for out-of-bounds\n index). \n\n getPointWeight\n\nC++: mrpt::maps::CPointsMap::setPointWeight(size_t, unsigned long) --> void", pybind11::arg("index"), pybind11::arg("w"));
cl.def("getPointWeight", (unsigned long (mrpt::maps::CPointsMap::*)(size_t) const) &mrpt::maps::CPointsMap::getPointWeight, "Gets the point weight, which is ignored in all classes (defaults to 1)\n but in those which actually store that field (Note: No checks are done\n for out-of-bounds index). \n\n setPointWeight\n\nC++: mrpt::maps::CPointsMap::getPointWeight(size_t) const --> unsigned long", pybind11::arg("index"));
cl.def("hasField_Intensity", (bool (mrpt::maps::CPointsMap::*)() const) &mrpt::maps::CPointsMap::hasField_Intensity, "C++: mrpt::maps::CPointsMap::hasField_Intensity() const --> bool");
cl.def("hasField_Ring", (bool (mrpt::maps::CPointsMap::*)() const) &mrpt::maps::CPointsMap::hasField_Ring, "C++: mrpt::maps::CPointsMap::hasField_Ring() const --> bool");
cl.def("hasField_Timestamp", (bool (mrpt::maps::CPointsMap::*)() const) &mrpt::maps::CPointsMap::hasField_Timestamp, "C++: mrpt::maps::CPointsMap::hasField_Timestamp() const --> bool");
Expand Down
Loading

0 comments on commit 3f63b96

Please sign in to comment.