Public Types | Static Public Member Functions | Static Public Attributes | List of all members
PointMatcher< T >::PointCloudGenerator Struct Reference

#include <PointMatcher.h>

Public Types

typedef Eigen::Transform< T, kPointDimension, Eigen::Affine > AffineTransform
 An affine transform over ScalarType of kPointDimension. More...
 
using Index = typename DataPoints::Index
 
typedef Eigen::Matrix< T, kPointDimension, 1 > StaticCoordVector
 A vector over ScalarType of kPointDimension. More...
 

Static Public Member Functions

static void addEmpty3dPointFields (const Index numberOfPoints, DataPoints &pointCloud)
 Adds 3D coordinates and normals fields to a point cloud. More...
 
static void applyTransformation (const StaticCoordVector &translation, const Quaternion &rotation, DataPoints &pointCloud)
 Transforms a point cloud by translating and rotating it a given amount. More...
 
static AffineTransform buildUpTransformation (const StaticCoordVector &translation, const Quaternion &rotation)
 Builds a 3D affine transformation with a given translation and rotation. More...
 
static StaticCoordVector computeNormalOfAxisAlignedPlane (const StaticCoordVector &axisAlignedPlaneDimensions)
 Computes a normal vector from a vector that contains the dimensions of a 2D shape in at-most 2 directions. More...
 
static DataPoints generateUniformlySampledBox (const ScalarType length, const ScalarType width, const ScalarType height, const Index numberOfPoints, const StaticCoordVector &translation, const Quaternion &rotation)
 Generates a uniformly sampled box (with no filling), with a given number of points and pose. More...
 
static DataPoints generateUniformlySampledCircle (const ScalarType radius, const Index numberOfPoints, const StaticCoordVector &translation, const Quaternion &rotation)
 Generates a uniformly sampled circle, with a given number of points and pose. More...
 
static DataPoints generateUniformlySampledCylinder (const ScalarType radius, const ScalarType height, const Index numberOfPoints, const StaticCoordVector &translation, const Quaternion &rotation)
 Generates a uniformly sampled cylinder (with no filling), with a given number of points and pose. More...
 
static DataPoints generateUniformlySampledPlane (const StaticCoordVector &dimensions, const Index numberOfPoints, const StaticCoordVector &translation, const Quaternion &rotation)
 Generates a uniformly sampled plane, with a given number of points and pose. More...
 
static DataPoints generateUniformlySampledSphere (const ScalarType radius, const Index numberOfPoints, const StaticCoordVector &translation, const Quaternion &rotation)
 Generates a uniformly sampled sphere (with no filling), with a given number of points and pose. More...
 

Static Public Attributes

static constexpr Eigen::Index kPointDimension { 3 }
 The dimension of the point clouds that libpointmatcher will process. More...
 
static constexpr ScalarType pi { static_cast<ScalarType>(M_PI) }
 Pi. More...
 

Detailed Description

template<typename T>
struct PointMatcher< T >::PointCloudGenerator

Definition at line 775 of file PointMatcher.h.

Member Typedef Documentation

◆ AffineTransform

template<typename T >
typedef Eigen::Transform<T, kPointDimension, Eigen::Affine> PointMatcher< T >::PointCloudGenerator::AffineTransform

An affine transform over ScalarType of kPointDimension.

Definition at line 780 of file PointMatcher.h.

◆ Index

template<typename T >
using PointMatcher< T >::PointCloudGenerator::Index = typename DataPoints::Index

Definition at line 784 of file PointMatcher.h.

◆ StaticCoordVector

A vector over ScalarType of kPointDimension.

Definition at line 782 of file PointMatcher.h.

Member Function Documentation

◆ addEmpty3dPointFields()

template<typename T >
void PointMatcher< T >::PointCloudGenerator::addEmpty3dPointFields ( const Index  numberOfPoints,
DataPoints pointCloud 
)
static

Adds 3D coordinates and normals fields to a point cloud.

Parameters
numberOfPoints[in]Number of points to add to the point cloud.
pointCloud[out]Point cloud.

Definition at line 52 of file pointmatcher/PointCloudGenerator.cpp.

◆ applyTransformation()

template<typename T >
void PointMatcher< T >::PointCloudGenerator::applyTransformation ( const StaticCoordVector translation,
const Quaternion rotation,
DataPoints pointCloud 
)
static

Transforms a point cloud by translating and rotating it a given amount.

Parameters
translation[in]Translation.
rotation[in]Rotation.
pointCloud[out]Point cloud to transform.

Definition at line 70 of file pointmatcher/PointCloudGenerator.cpp.

◆ buildUpTransformation()

template<typename T >
PointMatcher< T >::PointCloudGenerator::AffineTransform PointMatcher< T >::PointCloudGenerator::buildUpTransformation ( const StaticCoordVector translation,
const Quaternion rotation 
)
static

Builds a 3D affine transformation with a given translation and rotation.

Parameters
translationTranslation. [m]
rotationRotation quaternion.
Returns
AffineTransform Resulting transformation.

Definition at line 42 of file pointmatcher/PointCloudGenerator.cpp.

◆ computeNormalOfAxisAlignedPlane()

template<typename T >
PointMatcher< T >::PointCloudGenerator::StaticCoordVector PointMatcher< T >::PointCloudGenerator::computeNormalOfAxisAlignedPlane ( const StaticCoordVector axisAlignedPlaneDimensions)
static

Computes a normal vector from a vector that contains the dimensions of a 2D shape in at-most 2 directions.

Parameters
axisAlignedPlaneDimensions[in]Dimensions vector.
Returns
StaticCoordVector Normal vector.

Definition at line 84 of file pointmatcher/PointCloudGenerator.cpp.

◆ generateUniformlySampledBox()

template<typename T >
PointMatcher< T >::DataPoints PointMatcher< T >::PointCloudGenerator::generateUniformlySampledBox ( const ScalarType  length,
const ScalarType  width,
const ScalarType  height,
const Index  numberOfPoints,
const StaticCoordVector translation,
const Quaternion rotation 
)
static

Generates a uniformly sampled box (with no filling), with a given number of points and pose.

Parameters
length[in]Length of the box. [m]
width[in]Width of the box. [m]
height[in]Height of the box. [m]
numberOfPoints[in]Number of points.
translation[in]Translation with respect to the box origin, to be used for positioning the box.
rotation[in]Rotation with respect to the box origin, to be used for positioning the box.
Returns
DataPoints Box's point cloud.

Definition at line 312 of file pointmatcher/PointCloudGenerator.cpp.

◆ generateUniformlySampledCircle()

template<typename T >
PointMatcher< T >::DataPoints PointMatcher< T >::PointCloudGenerator::generateUniformlySampledCircle ( const ScalarType  radius,
const Index  numberOfPoints,
const StaticCoordVector translation,
const Quaternion rotation 
)
static

Generates a uniformly sampled circle, with a given number of points and pose.

Parameters
radius[in]Radius of the circle. [m]
numberOfPoints[in]Number of points.
translation[in]Translation with respect to the circle origin, to be used for positioning the circle.
rotation[in]Rotation with respect to the circle origin, to be used for positioning the circle.
Returns
DataPoints Circle's point cloud.

Definition at line 152 of file pointmatcher/PointCloudGenerator.cpp.

◆ generateUniformlySampledCylinder()

template<typename T >
PointMatcher< T >::DataPoints PointMatcher< T >::PointCloudGenerator::generateUniformlySampledCylinder ( const ScalarType  radius,
const ScalarType  height,
const Index  numberOfPoints,
const StaticCoordVector translation,
const Quaternion rotation 
)
static

Generates a uniformly sampled cylinder (with no filling), with a given number of points and pose.

Parameters
radius[in]Radius of the cylinder. [m]
height[in]Height of the cylinder. [m]
numberOfPoints[in]Number of points.
translation[in]Translation with respect to the cylinder origin, to be used for positioning the cylinder.
rotation[in]Rotation with respect to the cylinder origin, to be used for positioning the cylinder.
Returns
DataPoints Circle's point cloud.

Definition at line 198 of file pointmatcher/PointCloudGenerator.cpp.

◆ generateUniformlySampledPlane()

template<typename T >
PointMatcher< T >::DataPoints PointMatcher< T >::PointCloudGenerator::generateUniformlySampledPlane ( const StaticCoordVector dimensions,
const Index  numberOfPoints,
const StaticCoordVector translation,
const Quaternion rotation 
)
static

Generates a uniformly sampled plane, with a given number of points and pose.

Parameters
dimensions[in]Dimensions of the plane (length, width, height). [m]
numberOfPoints[in]Number of points.
translation[in]Translation with respect to the plane origin, to be used for positioning the plane.
rotation[in]Rotation with respect to the plane origin, to be used for positioning the plane.
Returns
DataPoints Plane's point cloud.

Definition at line 271 of file pointmatcher/PointCloudGenerator.cpp.

◆ generateUniformlySampledSphere()

template<typename T >
PointMatcher< T >::DataPoints PointMatcher< T >::PointCloudGenerator::generateUniformlySampledSphere ( const ScalarType  radius,
const Index  numberOfPoints,
const StaticCoordVector translation,
const Quaternion rotation 
)
static

Generates a uniformly sampled sphere (with no filling), with a given number of points and pose.

Parameters
radius[in]Radius of the sphere. [m]
numberOfPoints[in]Number of points.
translation[in]Translation with respect to the sphere origin, to be used for positioning the sphere.
rotation[in]Rotation with respect to the sphere origin, to be used for positioning the sphere.
Returns
DataPoints Sphere's point cloud.

Definition at line 100 of file pointmatcher/PointCloudGenerator.cpp.

Member Data Documentation

◆ kPointDimension

template<typename T >
constexpr Eigen::Index PointMatcher< T >::PointCloudGenerator::kPointDimension { 3 }
staticconstexpr

The dimension of the point clouds that libpointmatcher will process.

Definition at line 778 of file PointMatcher.h.

◆ pi

template<typename T >
constexpr ScalarType PointMatcher< T >::PointCloudGenerator::pi { static_cast<ScalarType>(M_PI) }
staticconstexpr

Pi.

Definition at line 868 of file PointMatcher.h.


The documentation for this struct was generated from the following files:


libpointmatcher
Author(s):
autogenerated on Mon Jul 1 2024 02:22:44