Functions for generating meshes for various types of shape primitives.
More...
|
| pcl::PolygonMesh | noether::createPlaneMesh (const float lx=1.0, const float ly=1.0, const Eigen::Isometry3d &origin=Eigen::Isometry3d::Identity()) |
| |
| pcl::PolygonMesh | noether::createEllipsoidMesh (const float rx=1.0, const float ry=1.0, const float rz=1.5, const std::size_t resolution=20lu, const float theta_range=static_cast< float >(M_PI), const float phi_range=static_cast< float >(2.0 *M_PI), const Eigen::Isometry3d &origin=Eigen::Isometry3d::Identity()) |
| |
| pcl::PolygonMesh | noether::createCylinderMesh (const float radius, const float length, const std::size_t resolution=20lu, std::size_t vertical_resolution=2u, const float theta_range=static_cast< float >(2.0 *M_PI), const bool include_caps=true, const Eigen::Isometry3d &origin=Eigen::Isometry3d::Identity()) |
| |
| pcl::PolygonMesh | noether::createCylinderMesh (const float radius, const float length, const std::size_t resolution=20lu, const float theta_range=static_cast< float >(2.0 *M_PI), const bool include_caps=true, const Eigen::Isometry3d &origin=Eigen::Isometry3d::Identity()) |
| |
| pcl::PolygonMesh | noether::createCylinderMeshWithUniformTriangles (const float radius, const float length, const std::size_t resolution=20lu, const float theta_range=static_cast< float >(2.0 *M_PI), const bool include_caps=true, const Eigen::Isometry3d &origin=Eigen::Isometry3d::Identity()) |
| |
◆ createPlaneMesh()
| pcl::PolygonMesh noether::createPlaneMesh |
( |
const float |
lx = 1.0, |
|
|
const float |
ly = 1.0, |
|
|
const Eigen::Isometry3d & |
origin = Eigen::Isometry3d::Identity() |
|
) |
| |
Creates a mesh of an x-y plane (z-axis is normal) with a specified length and width. The plane is comprised of 4 vertices and two triangles per the diagram below:
0 — 3
| A / |
| / B |
1 — 2
- Parameters
-
| lx | Length (m) along the x direction |
| ly | Length (m) along the y direction |
| origin | Transform to the desired origin of the primitive |
◆ createEllipsoidMesh()
| pcl::PolygonMesh noether::createEllipsoidMesh |
( |
const float |
rx = 1.0, |
|
|
const float |
ry = 1.0, |
|
|
const float |
rz = 1.5, |
|
|
const std::size_t |
resolution = 20lu, |
|
|
const float |
theta_range = static_cast<float>(M_PI), |
|
|
const float |
phi_range = static_cast<float>(2.0 * M_PI), |
|
|
const Eigen::Isometry3d & |
origin = Eigen::Isometry3d::Identity() |
|
) |
| |
Creates a mesh of an ellipsoid
- See also
- The implementation is adapted from Open3D
- Parameters
-
| rx | Radius (m) along the x direction |
| ry | Radius (m) along the y direction |
| rz | Radius (m) along the z direction |
| resolution | Number of vertices in each "ring" of the ellipsoid |
| theta_range | Angle range (radians) of the ellipsoid spanning between the two poles on (0, pi]. If the value is less than pi, an ellipsoid shell is created. |
| phi_range | Angle range (radians) around the z-axis that passes through both poles, on (0, 2 * pi]. If the value is less than 2 * pi, an ellipsoid shell is crated. |
| origin | Transform to the desired origin of the primitive |
Original function from Open3D under MIT license. Copyright (c) 2018-2023 www.open3d.org. Modified by Southwest Research Institute 10/2025.
◆ createCylinderMesh() [1/2]
| pcl::PolygonMesh noether::createCylinderMesh |
( |
const float |
radius, |
|
|
const float |
length, |
|
|
const std::size_t |
resolution = 20lu, |
|
|
std::size_t |
vertical_resolution = 2u, |
|
|
const float |
theta_range = static_cast<float>(2.0 * M_PI), |
|
|
const bool |
include_caps = true, |
|
|
const Eigen::Isometry3d & |
origin = Eigen::Isometry3d::Identity() |
|
) |
| |
Creates a mesh of a cylinder with optional end caps
- Parameters
-
| radius | Radius (m) of the cylinder |
| length | Length (m) of the cylinder |
| resolution | Number of vertices around the perimeter of the cylinder |
| vertical_resolution | Number of "rings" of vertices down the length of the cylinder (minimum 2) |
| theta_range | Angle range (radians) of the cylinder, on (0, 2 * pi]. If the value is less than 2 * pi, a cylinder shell is created |
| include_caps | Flag to indicate whether the caps of the cylinder should be included |
| origin | Transform to the desired origin of the primitive |
◆ createCylinderMesh() [2/2]
| pcl::PolygonMesh noether::createCylinderMesh |
( |
const float |
radius, |
|
|
const float |
length, |
|
|
const std::size_t |
resolution = 20lu, |
|
|
const float |
theta_range = static_cast<float>(2.0 * M_PI), |
|
|
const bool |
include_caps = true, |
|
|
const Eigen::Isometry3d & |
origin = Eigen::Isometry3d::Identity() |
|
) |
| |
◆ createCylinderMeshWithUniformTriangles()
| pcl::PolygonMesh noether::createCylinderMeshWithUniformTriangles |
( |
const float |
radius, |
|
|
const float |
length, |
|
|
const std::size_t |
resolution = 20lu, |
|
|
const float |
theta_range = static_cast<float>(2.0 * M_PI), |
|
|
const bool |
include_caps = true, |
|
|
const Eigen::Isometry3d & |
origin = Eigen::Isometry3d::Identity() |
|
) |
| |