Go to the documentation of this file.
12 #include <mrpt/containers/CDynamicGrid.h>
13 #include <mrpt/math/TPoint3D.h>
14 #include <mrpt/math/TPolygon2D.h>
15 #include <mrpt/opengl/TTriangle.h>
37 const mrpt::math::TPoint2Df& bbMin,
const mrpt::math::TPoint2Df& bbMax,
int numCells = 100);
41 const mrpt::math::TPolygon2D&
getContour()
const;
58 mutable std::optional<mrpt::math::TPolygon2D>
contour_;
64 template <
typename... Args>
66 :
mrpt::containers::CDynamicGrid<uint8_t>(
std::forward<Args>(
args)...)
71 float cell2float(
const uint8_t& v)
const override {
return v; }
74 mutable std::optional<SimpleOccGrid>
grid_;
87 mrpt::math::TPolygon2D
next;
91 size_t i,
const mrpt::math::TPolygon2D& p,
bool allowApproxEdges)
const;
94 const mrpt::math::TPolygon2D& rawGridContour,
const std::string& debugStr = {})
const;
mrpt::math::TPolygon2D internalGridContour() const
void setShapeManual(const mrpt::math::TPolygon2D &contour, const float zMin, const float zMax)
std::string asString() const
void internalGridFloodFill() const
void mergeWith(const Shape2p5 &s)
void debugSaveGridTo3DSceneFile(const mrpt::math::TPolygon2D &rawGridContour, const std::string &debugStr={}) const
std::optional< SimpleOccGrid > grid_
float cell2float(const uint8_t &v) const override
mrpt::math::TPolygon2D next
void internalGridFilterSpurious() const
SimpleOccGrid(Args &&... args)
std::optional< mrpt::math::TPolygon2D > contour_
void buildInit(const mrpt::math::TPoint2Df &bbMin, const mrpt::math::TPoint2Df &bbMax, int numCells=100)
std::optional< RemovalCandidate > lossOfRemovingVertex(size_t i, const mrpt::math::TPolygon2D &p, bool allowApproxEdges) const
void buildAddPoint(const mrpt::math::TPoint3Df &pt)
geometry_msgs::TransformStamped t
const mrpt::math::TPolygon2D & getContour() const
void computeShape() const
Computes contour_ from the contents in grid_.
void buildAddTriangle(const mrpt::opengl::TTriangle &t)
mrpt::math::TPolygon2D internalPrunePolygon(const mrpt::math::TPolygon2D &poly) const
mvsim
Author(s):
autogenerated on Wed May 28 2025 02:13:08