visionx::tools Namespace Reference

Namespaces

 detail
 

Classes

struct  FunctorWithReturnType
 Base class for functors with return value. More...
 
struct  is_shared_ptr
 
struct  is_shared_ptr< boost::shared_ptr< T > >
 
struct  is_shared_ptr< std::shared_ptr< T > >
 
class  PerpendicularPlaneFitting
 
struct  PlaneFittingResult
 
struct  PointCloudFunctor
 Functor creating a pcl::PointCloud<PointT> and passing it to function. More...
 
struct  PointCloudPtrFunctor
 Functor creating a pcl::PointCloud<PointT>::Ptr and passing it to function. More...
 

Enumerations

enum  PCLToDebugDrawerConversionMode { eConvertAsPoints, eConvertAsColors, eConvertAsLabels }
 

Functions

template<class LabeledPointT >
void addSegmentIndices (std::map< uint32_t, pcl::PointIndices > &segmentIndices, const pcl::PointCloud< LabeledPointT > &labeledCloud, bool excludeZero=false)
 Add indices of each segment's points to segmentIndices. More...
 
template<class LabeledPointT >
void addSegmentIndices (std::map< uint32_t, pcl::PointIndices::Ptr > &segmentIndices, const pcl::PointCloud< LabeledPointT > &labeledCloud, bool excludeZero=false)
 
template<typename T >
void arrayToVector (const T *dataArray, const int size, std::vector< T > &vec)
 
template<class FunctionT , class... Args>
void callWithPointCloud (const FunctionT &function, PointContentType type, Args... args)
 Overload of callWithPointCloud() for functions passed by const reference. More...
 
template<class FunctionT , class... Args>
void callWithPointCloud (FunctionT &function, PointContentType type, Args... args)
 Call function with a pcl::PointCloud<PointT> with the adequate PointT according to type. More...
 
template<class FunctionT , class... Args>
void callWithPointCloudPtr (const FunctionT &function, PointContentType type, Args... args)
 Overload of callWithPointCloudPtr() for functions passed by const reference. More...
 
template<class FunctionT , class... Args>
void callWithPointCloudPtr (FunctionT &function, PointContentType type, Args... args)
 Call function with a (non-null) pcl::PointCloud<PointT>::Ptr with the adequate PointT according to type. More...
 
template<class FunctorT , class... Args>
std::enable_if_t< !std::is_base_of< detail::FunctorWithReturnType, FunctorT >::value, void > callWithPointType (const FunctorT &functor, PointContentType type, Args... args)
 Overload of visitWithPointType() for functors passed by const reference. More...
 
template<class VisitorT , class... Args>
VisitorT::ReturnType callWithPointType (const VisitorT &functor, PointContentType type, Args... args)
 Overload of visitWithPointType() for functors with return value passed by const reference. More...
 
template<class FunctorT , class... Args>
std::enable_if_t< !std::is_base_of< detail::FunctorWithReturnType, FunctorT >::value, void > callWithPointType (FunctorT &functor, PointContentType type, Args... args)
 Call functor with the correct pcl point type according to type. More...
 
template<class VisitorT , class... Args>
VisitorT::ReturnType callWithPointType (VisitorT &functor, PointContentType type, Args... args)
 Overload of visitWithPointType() for functors with return value. More...
 
void colorizeLabeledPointCloud (pcl::PointCloud< pcl::PointXYZL >::Ptr sourceCloudPtr, pcl::PointCloud< pcl::PointXYZRGBA >::Ptr targetCloudPtr)
 
template<typename PointCloudPtrT >
std::tuple< uint8_t, uint8_t, uint8_t > colorizeSegment (PointCloudPtrT &segment)
 
::ImageProcessor::BayerPatternType convert (const BayerPatternType visionxBayerPatternType)
 Converts a VisionX BayerPatternType into a IVT's image processor BayerPatternType. More...
 
visionx::MonocularCalibration convert (const CCalibration &ivtCalibration)
 Converts an IVT CCalibration into a VisionX MonocularCalibration struct. More...
 
visionx::StereoCalibration convert (const CStereoCalibration &ivtStereoCalibration)
 Converts an IVT CStereoCalibration into a VisionX StereoCalibration struct. More...
 
CVideoCaptureInterface::FrameRate convert (const float frameRate)
 Converts frame rate floats into distinct IVT FrameRates by applying quantization. More...
 
CVideoCaptureInterface::VideoMode convert (const ImageDimension &imageDimension)
 Converts a VisionX image dimension object into an IVT VideoMode of IVT's CVideoCaptureInterface. More...
 
CByteImage::ImageType convert (const ImageType visionxImageType)
 Converts a VisionX image type into an image type of IVT's ByteImage. More...
 
visionx::types::Mat convert (const Mat3d &mat)
 Converts an IVT Mat3d into VisionX Matrix (float STL Vectors) More...
 
visionx::types::Region convert (const MyRegion &ivtRegion)
 Converts an IVT MyRegion into a VisionX MyRegion. More...
 
visionx::types::Object3DEntry convert (const Object3DEntry &ivtObject3DEntry)
 Converts an IVT Object3DEntry id into a VisionX ObjectEntry. More...
 
visionx::types::Object3DList convert (const Object3DList &ivtObject3DList)
 Converts an IVT Object3DList object into an VisionX ObjectList. More...
 
visionx::types::ObjectColor convert (const ObjectColor &ivtObjectColor)
 Mapps an IVT Object color id onto a VisionX object color id. More...
 
visionx::types::ObjectType convert (const ObjectType &ivtObjectType)
 Mapps an IVT Object type id onto a VisionX object type id. More...
 
visionx::types::Transformation3d convert (const Transformation3d &ivtTransformation3d)
 Converts an IVT Transformation3d into a VisionX Transformation3d. More...
 
visionx::types::Vec convert (const Vec2d &vec)
 Converts an IVT Vec2d Vector into VisionX Vector (float STL Vector) More...
 
visionx::types::Vec convert (const Vec3d &vec)
 Converts an IVT Vec3d Vector into VisionX Vector (float STL Vector) More...
 
CCalibration * convert (const visionx::MonocularCalibration &calibration)
 Converts a VisionX MonocularCalibration object into an IVT CCalibration. More...
 
CStereoCalibration * convert (const visionx::StereoCalibration &stereoCalibration)
 Converts a VisionX StereoCalibration object into an IVT CStereoCalibration. More...
 
Mat3d convert (const visionx::types::Mat &mat)
 Converts a VisionX Matrix (float STL Vectors) into an IVT Mat3d. More...
 
Object3DEntry convert (const visionx::types::Object3DEntry &object3DEntry)
 Converts a VisionX ObjectEntry object into an IVT Object3DEntry instance. More...
 
Object3DList convert (const visionx::types::Object3DList &object3DList)
 Converts an IVT Object3DList object into a VisionX Object3DEntry instance. More...
 
ObjectColor convert (const visionx::types::ObjectColor &objectColor)
 Mapps an IVT Object color id onto a VisionX object color id. More...
 
ObjectType convert (const visionx::types::ObjectType &objectType)
 Mapps an IVT Object type id onto a VisionX object type id. More...
 
MyRegion convert (const visionx::types::Region &region)
 Converts a VisionX MyRegion object into an IVT MyRegion instance. More...
 
Transformation3d convert (const visionx::types::Transformation3d &transformation3d)
 Converts a VisionX Transformation3d object into an IVT Transformation3d object. More...
 
Vec3d convert (const visionx::types::Vec &vec)
 Converts a VisionX Vector (float STL Vector) into an IVT Vec3d. More...
 
Vec2d convert (const visionx::types::Vec *pVec)
 Converts a VisionX Vector (float STL Vector) into an IVT Vec2d. More...
 
visionx::types::Mat convertEigenMatToVisionX (Eigen::MatrixXf m)
 
visionx::types::Vec convertEigenVecToVisionX (Eigen::VectorXf v)
 
void convertFromPCL (const pcl::PointCloud< pcl::PointXYZRGBA >::Ptr sourcePtr, ColoredPointCloud &target)
 
void convertFromPCL (const pcl::PointCloud< pcl::PointXYZRGBA >::Ptr sourcePtr, visionx::ColoredPointCloud &target)
 
void convertFromPCL (const pcl::PointCloud< pcl::PointXYZRGBL > &source, ColoredLabeledPointCloud &target)
 
template<typename VisionXPointT , typename PclPointT >
std::vector< VisionXPointT > convertFromPCL (const pcl::PointCloud< PclPointT > &source)
 Convert a PCL point cloud to a VisionX point cloud (as return value). More...
 
template<typename VisionXPointT , typename PclPointT >
void convertFromPCL (const pcl::PointCloud< PclPointT > &source, std::vector< VisionXPointT > &target)
 Convert a PCL point cloud to a VisionX point cloud. More...
 
void convertFromPCL (pcl::PointCloud< pcl::PointXYZ >::Ptr sourcePtr, void **target)
 
void convertFromPCL (pcl::PointCloud< pcl::PointXYZI >::Ptr sourcePtr, void **target)
 
void convertFromPCL (pcl::PointCloud< pcl::PointXYZL >::Ptr sourcePtr, void **target)
 
void convertFromPCL (pcl::PointCloud< pcl::PointXYZRGB >::Ptr sourcePtr, void **target)
 
void convertFromPCL (pcl::PointCloud< pcl::PointXYZRGBA >::Ptr sourcePtr, void **target)
 
void convertFromPCL (pcl::PointCloud< pcl::PointXYZRGBL >::Ptr sourcePtr, void **target)
 
void convertFromPCL (pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr &sourcePtr, void **target)
 
void convertFromPCLToDebugDrawer (const pcl::PointCloud< pcl::PointXYZ >::Ptr &sourcePtr, armarx::DebugDrawer24BitColoredPointCloud &target, PCLToDebugDrawerConversionMode mode, float pointSize)
 
void convertFromPCLToDebugDrawer (const pcl::PointCloud< pcl::PointXYZL >::Ptr &sourcePtr, armarx::DebugDrawer24BitColoredPointCloud &target, PCLToDebugDrawerConversionMode mode, float pointSize)
 
void convertFromPCLToDebugDrawer (const pcl::PointCloud< pcl::PointXYZRGBA >::Ptr &sourcePtr, armarx::DebugDrawer24BitColoredPointCloud &target, PCLToDebugDrawerConversionMode mode, float pointSize)
 
void convertFromPCLToDebugDrawer (const pcl::PointCloud< pcl::PointXYZRGBL >::Ptr &sourcePtr, armarx::DebugDrawer24BitColoredPointCloud &target, PCLToDebugDrawerConversionMode mode, float pointSize)
 
void convertImage (const ImageFormatInfo &imageFormat, const ImageType destinationImageType, void *inputData, void *outputData)
 This converts the input image data into a desired destination image data type specified in the given ImageProviderInfo. More...
 
void convertImage (const ImageProviderInfo &imageProviderInfo, void *inputData, void *outputData)
 Simplifies usage of visionx::tools:convertImage in ImageProcessors. More...
 
Eigen::Matrix3f convertIVTtoEigen (const Mat3d m)
 
Eigen::Vector3f convertIVTtoEigen (const Vec3d v)
 
template<>
void convertPointFromPCL (const pcl::PointXYZ &source, visionx::Point3D &target)
 
template<>
void convertPointFromPCL (const pcl::PointXYZL &source, visionx::LabeledPoint3D &target)
 
template<>
void convertPointFromPCL (const pcl::PointXYZRGBA &source, visionx::ColoredPoint3D &target)
 
template<>
void convertPointFromPCL (const pcl::PointXYZRGBL &source, visionx::ColoredLabeledPoint3D &target)
 
template<typename PclPointT , typename VisionXPointT >
void convertPointFromPCL (const PclPointT &p, VisionXPointT &v)
 Convert a PCL point type to a VisionX point type. More...
 
template<>
void convertPointToPCL (const visionx::ColoredLabeledPoint3D &source, pcl::PointXYZRGBL &target)
 
template<>
void convertPointToPCL (const visionx::ColoredPoint3D &source, pcl::PointXYZRGBA &target)
 
template<>
void convertPointToPCL (const visionx::LabeledPoint3D &source, pcl::PointXYZL &target)
 
template<>
void convertPointToPCL (const visionx::Point3D &source, pcl::PointXYZ &target)
 
template<typename PclPointT , typename VisionXPointT >
void convertPointToPCL (const VisionXPointT &v, PclPointT &p)
 Convert a VisionX point type to a PCL point type. More...
 
void convertToPCL (const ColoredLabeledPointCloud &source, pcl::PointCloud< pcl::PointXYZRGBL > &target)
 
void convertToPCL (const ColoredPointCloud &source, pcl::PointCloud< pcl::PointXYZRGBA >::Ptr targetPtr)
 
template<typename PclPointT , typename VisionXPointT >
pcl::PointCloud< PclPointT >::Ptr convertToPCL (const std::vector< VisionXPointT > &source)
 Convert a VisionX point cloud to a PCL point cloud (as return value). More...
 
template<typename PclPointT , typename VisionXPointT >
void convertToPCL (const std::vector< VisionXPointT > &source, pcl::PointCloud< PclPointT > &target)
 Convert a VisionX point cloud to a PCL point cloud. More...
 
void convertToPCL (const visionx::ColoredPointCloud &source, pcl::PointCloud< pcl::PointXYZRGBA >::Ptr targetPtr)
 
void convertToPCL (void **source, visionx::MetaPointCloudFormatPtr pointCloudFormat, pcl::PointCloud< pcl::PointXYZ >::Ptr targetPtr)
 
void convertToPCL (void **source, visionx::MetaPointCloudFormatPtr pointCloudFormat, pcl::PointCloud< pcl::PointXYZI >::Ptr targetPtr)
 
void convertToPCL (void **source, visionx::MetaPointCloudFormatPtr pointCloudFormat, pcl::PointCloud< pcl::PointXYZL >::Ptr targetPtr)
 
void convertToPCL (void **source, visionx::MetaPointCloudFormatPtr pointCloudFormat, pcl::PointCloud< pcl::PointXYZRGB >::Ptr targetPtr)
 
void convertToPCL (void **source, visionx::MetaPointCloudFormatPtr pointCloudFormat, pcl::PointCloud< pcl::PointXYZRGBA >::Ptr targetPtr)
 
void convertToPCL (void **source, visionx::MetaPointCloudFormatPtr pointCloudFormat, pcl::PointCloud< pcl::PointXYZRGBL >::Ptr targetPtr)
 
void convertToPCL (void **source, visionx::MetaPointCloudFormatPtr pointCloudFormat, pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr targetPtr)
 
CByteImage * createByteImage (const ImageFormatInfo &imageFormat)
 
CByteImage * createByteImage (const ImageFormatInfo &imageFormat, const ImageType imageType)
 Creates a ByteImage for the destination type specified in the given imageProviderInfo. More...
 
CByteImage * createByteImage (const ImageProviderInfo &imageProviderInfo)
 Simplifies usage of visionx::tools:convertImage in ImageProcessors. More...
 
MonocularCalibration createDefaultMonocularCalibration ()
 Creates a MonocularCalibration with all parameters set to a neutral value. More...
 
CFloatImage * createFloatImage (const ImageFormatInfo &imageFormat, const ImageType imageType)
 Creates a FloatImage for the destination type specified in the given imageProviderInfo. More...
 
CFloatImage * createFloatImage (const ImageProviderInfo &imageProviderInfo)
 Simplifies usage of visionx::tools:convertImage in ImageProcessors. More...
 
 DECLARE_fitPlaneRansac_PointT (pcl::PointXYZ)
 
 DECLARE_fitPlaneRansac_PointT (pcl::PointXYZRGB)
 
 DECLARE_fitPlaneRansac_PointT (pcl::PointXYZRGBA)
 
 DECLARE_fitPlaneRansac_PointT (pcl::PointXYZRGBL)
 
void depthValueToRGB (unsigned int depthInMM, unsigned char &r, unsigned char &g, unsigned char &b, bool noiseResistant=false)
 
template<typename PointCloudT >
PointCloudT::Ptr downsampleByVoxelGrid (typename PointCloudT::ConstPtr inputCloud, float leafSize=5.0, pcl::IndicesConstPtr indices=nullptr)
 
template<typename PointCloudT >
PointCloudT::Ptr downsampleByVoxelGrid (typename PointCloudT::ConstPtr inputCloud, float leafSize=5.0, pcl::PointIndicesConstPtr indices=nullptr)
 
template<class PointCloudT >
std::enable_if<!is_shared_ptr< PointCloudT >::value, void >::type fillLabelMap (const PointCloudT &labeledCloud, std::map< uint32_t, pcl::PointIndices > &labelIndicesMap, bool excludeZero=true)
 
template<class LabeledPointCloudPtrT >
std::enable_if< is_shared_ptr< LabeledPointCloudPtrT >::value, void >::type fillLabelMap (LabeledPointCloudPtrT labeledCloudPtr, std::map< uint32_t, pcl::PointIndices > &labelIndicesMap, bool excludeZero=true)
 
template<typename PointT , typename IndicesPtrT = pcl::IndicesPtr>
std::optional< PlaneFittingResultfitPlaneRansac (typename pcl::PointCloud< PointT >::Ptr cloud, double distanceThreshold=1.0, const IndicesPtrT &indices=nullptr)
 
template<typename PointCloudT >
simox::AxisAlignedBoundingBox getAABB (const PointCloudT &pointCloud, const pcl::PointIndices &indices={})
 Get the axis-aligned bounding-box of the given point cloud. More...
 
template<class PointCloudT >
simox::AxisAlignedBoundingBox getAABB (const PointCloudT &pointCloud, const pcl::PointIndices::Ptr &indices)
 
size_t getBytesPerPoint (visionx::PointContentType pointContent)
 
template<typename PointCloudT >
pcl::PointIndices::Ptr getCropIndices (const PointCloudT &inputCloud, Eigen::Vector3f min, Eigen::Vector3f max)
 
template<typename PointCloudT >
PointCloudT::Ptr getCropped (const PointCloudT &inputCloud, Eigen::Vector3f min, Eigen::Vector3f max)
 
std::string getHardwareId ()
 Retrieve hardware id to identify local machine. More...
 
template<class PointCloudT >
std::map< uint32_t, pcl::PointIndices > getLabelMap (const PointCloudT &labeledCloud, bool excludeZero=true)
 
template<typename LabeledPointT >
std::set< uint32_t > getLabelSet (const pcl::PointCloud< LabeledPointT > &pointCloud)
 Return the set of labels in pointCloud. More...
 
template<class ValueT >
std::set< uint32_t > getLabelSet (const std::map< uint32_t, ValueT > &segmentIndices)
 Return the labels in segmentIndices as std::set. More...
 
template<typename PointT >
visionx::PointContentType getPointContentType ()
 
template<>
PointContentType getPointContentType< pcl::PointNormal > ()
 
template<>
visionx::PointContentType getPointContentType< pcl::PointXYZ > ()
 
template<>
visionx::PointContentType getPointContentType< pcl::PointXYZI > ()
 
template<>
visionx::PointContentType getPointContentType< pcl::PointXYZL > ()
 
template<>
visionx::PointContentType getPointContentType< pcl::PointXYZRGBA > ()
 
template<>
visionx::PointContentType getPointContentType< pcl::PointXYZRGBL > ()
 
template<>
visionx::PointContentType getPointContentType< pcl::PointXYZRGBNormal > ()
 
template<class PointT , class IndicesT = pcl::PointIndices>
std::map< uint32_t, simox::AxisAlignedBoundingBox > getSegmentAABBs (const pcl::PointCloud< PointT > &pointCloud, const std::map< uint32_t, IndicesT > &segmentIndices)
 
template<class PointT , class IndicesT = pcl::PointIndices>
std::vector< simox::AxisAlignedBoundingBox > getSegmentAABBs (const pcl::PointCloud< PointT > &pointCloud, const std::vector< IndicesT > &segmentIndices)
 
template<class LabeledPointT >
std::map< uint32_t, pcl::PointIndices > getSegmentIndices (const pcl::PointCloud< LabeledPointT > &labeledCloud, bool excludeZero=false)
 Get a map from segment labels to indices of segments' points. More...
 
template<class LabeledPointT >
std::map< uint32_t, pcl::PointIndices::Ptr > getSegmentIndicesPtr (const pcl::PointCloud< LabeledPointT > &labeledCloud, bool excludeZero=false)
 Version of addSegmentIndices() containing pcl::PointIndices::Ptr. More...
 
template<class ValueT >
std::vector< uint32_t > getUniqueLabels (const std::map< uint32_t, ValueT > &segmentIndices)
 Return the labels in segmentIndices as std::vector. More...
 
std::string imageTypeToTypeName (const ImageType imageType)
 Converts an image type into a string integer. More...
 
bool isColored (PointContentType type)
 
bool isColored (visionx::PointContentType type)
 Indicate whether this point type contains colors. More...
 
bool isLabeled (PointContentType type)
 
bool isLabeled (visionx::PointContentType type)
 Indicate whether this point type contains labels. More...
 
template<class PointT >
void relabel (pcl::PointCloud< PointT > &pointCloud, const std::map< uint32_t, pcl::PointIndices > &segmentIndices)
 
template<class PointT >
void relabel (pcl::PointCloud< PointT > &pointCloud, const std::map< uint32_t, pcl::PointIndices::Ptr > &segmentIndices)
 
float rgbToDepthValue (unsigned char r, unsigned char g, unsigned char b, bool noiseResistant=false)
 
simox::AxisAlignedBoundingBox toAABB (const BoundingBox3D &boundingBox)
 
BoundingBox3D toBoundingBox3D (const Eigen::Vector3f &min, const Eigen::Vector3f &max)
 
BoundingBox3D toBoundingBox3D (const simox::AxisAlignedBoundingBox &aabb)
 
std::string toString (PointContentType pointContent)
 
std::string toString (visionx::PointContentType pointContent)
 
ImageType typeNameToImageType (const std::string &imageTypeName)
 Converts an image type name as string into an ImageType integer. More...
 
template<typename T >
TvectorToArray (const std::vector< T > &dataVector)
 

Enumeration Type Documentation

◆ PCLToDebugDrawerConversionMode

Enumerator
eConvertAsPoints 
eConvertAsColors 
eConvertAsLabels 

Definition at line 102 of file PointCloudConversions.h.

Function Documentation

◆ addSegmentIndices() [1/2]

void visionx::tools::addSegmentIndices ( std::map< uint32_t, pcl::PointIndices > &  segmentIndices,
const pcl::PointCloud< LabeledPointT > &  labeledCloud,
bool  excludeZero = false 
)

Add indices of each segment's points to segmentIndices.

Parameters
segmentIndicesThe map to fill (label -> point indicies).
labeledCloudA labeled point cloud.
excludeZeroIf true, points with label == 0 are ignored.

Definition at line 52 of file segments.h.

+ Here is the call graph for this function:
+ Here is the caller graph for this function:

◆ addSegmentIndices() [2/2]

void visionx::tools::addSegmentIndices ( std::map< uint32_t, pcl::PointIndices::Ptr > &  segmentIndices,
const pcl::PointCloud< LabeledPointT > &  labeledCloud,
bool  excludeZero = false 
)

Definition at line 60 of file segments.h.

+ Here is the call graph for this function:

◆ arrayToVector()

void visionx::tools::arrayToVector ( const T dataArray,
const int  size,
std::vector< T > &  vec 
)

Definition at line 76 of file TypeMapping.h.

+ Here is the caller graph for this function:

◆ callWithPointCloud() [1/2]

void visionx::tools::callWithPointCloud ( const FunctionT &  function,
PointContentType  type,
Args...  args 
)

Overload of callWithPointCloud() for functions passed by const reference.

Definition at line 286 of file call_with_point_type.h.

+ Here is the call graph for this function:

◆ callWithPointCloud() [2/2]

void visionx::tools::callWithPointCloud ( FunctionT &  function,
PointContentType  type,
Args...  args 
)

Call function with a pcl::PointCloud<PointT> with the adequate PointT according to type.

The passed function may be a lambda taking the point cloud by auto as its first argument: [](auto pointCloud) { pointCloud.size(); }

Parameters
functionThe function to be called.
typeThe point content type.
argsOptional additional arguments passed to the called function.

Definition at line 279 of file call_with_point_type.h.

+ Here is the call graph for this function:

◆ callWithPointCloudPtr() [1/2]

void visionx::tools::callWithPointCloudPtr ( const FunctionT &  function,
PointContentType  type,
Args...  args 
)

Overload of callWithPointCloudPtr() for functions passed by const reference.

Definition at line 310 of file call_with_point_type.h.

+ Here is the call graph for this function:

◆ callWithPointCloudPtr() [2/2]

void visionx::tools::callWithPointCloudPtr ( FunctionT &  function,
PointContentType  type,
Args...  args 
)

Call function with a (non-null) pcl::PointCloud<PointT>::Ptr with the adequate PointT according to type.

The passed function may be a lambda taking the point cloud by auto as its first argument: [](auto pointCloud) { pointCloud->size(); }

Parameters
functionThe function to be called.
typeThe point content type.
argsOptional additional arguments passed to the called function.

Definition at line 303 of file call_with_point_type.h.

+ Here is the call graph for this function:

◆ callWithPointType() [1/4]

std::enable_if_t< !std::is_base_of<detail::FunctorWithReturnType, FunctorT>::value, void > visionx::tools::callWithPointType ( const FunctorT &  functor,
PointContentType  type,
Args...  args 
)

Overload of visitWithPointType() for functors passed by const reference.

Definition at line 136 of file call_with_point_type.h.

◆ callWithPointType() [2/4]

VisitorT::ReturnType visionx::tools::callWithPointType ( const VisitorT &  functor,
PointContentType  type,
Args...  args 
)

Overload of visitWithPointType() for functors with return value passed by const reference.

Definition at line 202 of file call_with_point_type.h.

◆ callWithPointType() [3/4]

std::enable_if_t< !std::is_base_of<detail::FunctorWithReturnType, FunctorT>::value, void > visionx::tools::callWithPointType ( FunctorT &  functor,
PointContentType  type,
Args...  args 
)

Call functor with the correct pcl point type according to type.

The passed functor must have a member functor template, taking the pcl point type as first template argument:

struct ExampleFunctor
{
template <class PointT>
void operator()()
{
pcl::PointCloud<PointT> pointCloud;
// Do stuff with `pointCloud` ...
(void) pointCloud;
}
};

Construct your functor and pass it to callWithPointType() along with the respective PointContentType:

PointContentType type = getPointContentType();
ExampleFunctor functor;

Depending on the passed PointContentType, the functor's operator() is called with the according pcl::Point... type as template argument. This allows you to create pcl::PointCloud<PointT> with the correct type.

In addition to functor and type, callWithPointType() can take more arguments which will be passed to the functor's operator():

struct ExampleFunctorTakingArguments
{
template <class PointT>
void operator()(int myInt, float myFloat)
{
(void) myInt;
(void) myFloat;
}
};

Usage:

PointContentType type = getPointContentType();
ExampleFunctorTakingArguments functor;
int myInt = 42;
float myFloat = 15;
visionx::tools::callWithPointType(functor, type, myInt, myFloat);

If your functor returns a result, have it derive from FunctorWithReturnType, specifying the return type as template argument:

struct ExampleFunctorReturningInt : visionx::tools::FunctorWithReturnType<int>
{
template <class PointT>
int operator()(int myArg)
{
return myArg + 42;
}
};

Usage:

PointContentType type = getPointContentType();
ExampleFunctorReturningInt functor;
int myInt = 42;
int result = visionx::tools::callWithPointType(functor, type, myInt);
Parameters
functorThe functor to be called.
typeThe point content type.
argsArguments passed to functor call.

Definition at line 104 of file call_with_point_type.h.

+ Here is the caller graph for this function:

◆ callWithPointType() [4/4]

VisitorT::ReturnType visionx::tools::callWithPointType ( VisitorT &  functor,
PointContentType  type,
Args...  args 
)

Overload of visitWithPointType() for functors with return value.

Definition at line 168 of file call_with_point_type.h.

◆ colorizeLabeledPointCloud()

void visionx::tools::colorizeLabeledPointCloud ( pcl::PointCloud< pcl::PointXYZL >::Ptr  sourceCloudPtr,
pcl::PointCloud< pcl::PointXYZRGBA >::Ptr  targetCloudPtr 
)
inline

Definition at line 65 of file PCLUtilities.h.

◆ colorizeSegment()

std::tuple<uint8_t, uint8_t, uint8_t> visionx::tools::colorizeSegment ( PointCloudPtrT &  segment)

Definition at line 48 of file PCLUtilities.h.

+ Here is the caller graph for this function:

◆ convert() [1/26]

ImageProcessor::BayerPatternType convert ( const BayerPatternType  visionxBayerPatternType)

Converts a VisionX BayerPatternType into a IVT's image processor BayerPatternType.

Parameters
visionxBayerPatternTypeVisionX Bayer pattern type
Returns
ImageProcessor::BayerPatternType

Definition at line 118 of file TypeMapping.cpp.

◆ convert() [2/26]

visionx::MonocularCalibration convert ( const CCalibration &  ivtCalibration)

Converts an IVT CCalibration into a VisionX MonocularCalibration struct.

Parameters
ivtCalibrationIVT Calibration
Returns
VisionX StereoCalibration object

Definition at line 436 of file TypeMapping.cpp.

+ Here is the call graph for this function:

◆ convert() [3/26]

visionx::StereoCalibration convert ( const CStereoCalibration &  ivtStereoCalibration)

Converts an IVT CStereoCalibration into a VisionX StereoCalibration struct.

Parameters
ivtStereoCalibrationIVT StereoCalibration
Returns
VisionX StereoCalibration object

Definition at line 391 of file TypeMapping.cpp.

+ Here is the call graph for this function:

◆ convert() [4/26]

CVideoCaptureInterface::FrameRate convert ( const float  frameRate)

Converts frame rate floats into distinct IVT FrameRates by applying quantization.

Parameters
frameRateframe rate
Returns
Closest CVideoCaptureInterface::FrameRate

Definition at line 175 of file TypeMapping.cpp.

◆ convert() [5/26]

CVideoCaptureInterface::VideoMode convert ( const ImageDimension &  imageDimension)

Converts a VisionX image dimension object into an IVT VideoMode of IVT's CVideoCaptureInterface.

Parameters
imageDimensionVisionX image dimension which consist of image width and height
Returns
According CVideoCaptureInterface::VideoMode if a valid dimension was passed otherwise CVideoCaptureInterface::eNone is returned.

Definition at line 141 of file TypeMapping.cpp.

◆ convert() [6/26]

CByteImage::ImageType convert ( const ImageType  visionxImageType)

Converts a VisionX image type into an image type of IVT's ByteImage.

Parameters
visionXImageTypeVisionX image type
Returns
ByteImage::ImageType

Definition at line 95 of file TypeMapping.cpp.

+ Here is the call graph for this function:
+ Here is the caller graph for this function:

◆ convert() [7/26]

visionx::types::Mat convert ( const Mat3d &  mat)

Converts an IVT Mat3d into VisionX Matrix (float STL Vectors)

Parameters
vecIVT 3D Matrix
Returns
VisionX matrix

Definition at line 274 of file TypeMapping.cpp.

◆ convert() [8/26]

visionx::types::Region convert ( const MyRegion &  ivtRegion)

Converts an IVT MyRegion into a VisionX MyRegion.

Parameters
ivtRegionIVT MyRegion struct instance
Returns
VisionX MyRegion object

Definition at line 458 of file TypeMapping.cpp.

+ Here is the call graph for this function:

◆ convert() [9/26]

visionx::types::Object3DEntry convert ( const Object3DEntry &  ivtObject3DEntry)

Converts an IVT Object3DEntry id into a VisionX ObjectEntry.

Parameters
ivtObject3DEntryIVT Object3DEntry
Returns
VisionX ObjectEntry

Definition at line 570 of file TypeMapping.cpp.

+ Here is the call graph for this function:

◆ convert() [10/26]

visionx::types::Object3DList convert ( const Object3DList &  ivtObject3DList)

Converts an IVT Object3DList object into an VisionX ObjectList.

Parameters
ivtObject3DListIVT Object3DList instance
Returns
VisionX ObjectList

Definition at line 613 of file TypeMapping.cpp.

+ Here is the call graph for this function:

◆ convert() [11/26]

visionx::types::ObjectColor convert ( const ObjectColor &  ivtObjectColor)

Mapps an IVT Object color id onto a VisionX object color id.

Parameters
ivtObjectColorIVT Object color id
Returns
VisionX Object color id

Definition at line 498 of file TypeMapping.cpp.

◆ convert() [12/26]

visionx::types::ObjectType convert ( const ObjectType &  ivtObjectType)

Mapps an IVT Object type id onto a VisionX object type id.

Parameters
ivtObjectTypeIVT Object type id
Returns
VisionX Object type id

Definition at line 510 of file TypeMapping.cpp.

◆ convert() [13/26]

visionx::types::Transformation3d convert ( const Transformation3d &  ivtTransformation3d)

Converts an IVT Transformation3d into a VisionX Transformation3d.

Parameters
ivtTransformation3dIVT Transformation3d struct instance
Returns
VisionX Transformation3d object

Definition at line 522 of file TypeMapping.cpp.

+ Here is the call graph for this function:

◆ convert() [14/26]

visionx::types::Vec convert ( const Vec2d &  vec)

Converts an IVT Vec2d Vector into VisionX Vector (float STL Vector)

Parameters
vecIVT 2D Vector
Returns
VisionX vector

Definition at line 253 of file TypeMapping.cpp.

◆ convert() [15/26]

visionx::types::Vec convert ( const Vec3d &  vec)

Converts an IVT Vec3d Vector into VisionX Vector (float STL Vector)

Parameters
vecIVT 3D Vector
Returns
VisionX vector

Definition at line 263 of file TypeMapping.cpp.

◆ convert() [16/26]

CCalibration * convert ( const visionx::MonocularCalibration &  calibration)

Converts a VisionX MonocularCalibration object into an IVT CCalibration.

Parameters
calibrationVisionX Stereo Calibration struct
Returns
IVT CCalibration

Definition at line 363 of file TypeMapping.cpp.

+ Here is the call graph for this function:

◆ convert() [17/26]

CStereoCalibration * convert ( const visionx::StereoCalibration &  stereoCalibration)

Converts a VisionX StereoCalibration object into an IVT CStereoCalibration.

Parameters
stereoCalibrationVisionX Stereo Calibration struct
Returns
IVT CStereoCalibration

Definition at line 300 of file TypeMapping.cpp.

+ Here is the call graph for this function:

◆ convert() [18/26]

Mat3d convert ( const visionx::types::Mat &  mat)

Converts a VisionX Matrix (float STL Vectors) into an IVT Mat3d.

Parameters
vecVisionX matrix
Returns
IVT 3D Matrix

Definition at line 230 of file TypeMapping.cpp.

◆ convert() [19/26]

Object3DEntry convert ( const visionx::types::Object3DEntry &  object3DEntry)

Converts a VisionX ObjectEntry object into an IVT Object3DEntry instance.

Parameters
objectEntryVisionX ObjectEntry object
Returns
IVT Object3DEntry object

Definition at line 544 of file TypeMapping.cpp.

+ Here is the call graph for this function:

◆ convert() [20/26]

Object3DList convert ( const visionx::types::Object3DList &  object3DList)

Converts an IVT Object3DList object into a VisionX Object3DEntry instance.

Parameters
objectListVisionX Object3DEntry instance
Returns
IVT Object3DList instance

Definition at line 594 of file TypeMapping.cpp.

+ Here is the call graph for this function:

◆ convert() [21/26]

ObjectColor convert ( const visionx::types::ObjectColor &  objectColor)

Mapps an IVT Object color id onto a VisionX object color id.

Parameters
objectColorVisionX object color id
Returns
IVT object color id

Definition at line 504 of file TypeMapping.cpp.

◆ convert() [22/26]

ObjectType convert ( const visionx::types::ObjectType &  objectType)

Mapps an IVT Object type id onto a VisionX object type id.

Parameters
objectTypeVisionX object type id
Returns
IVT object type id

Definition at line 516 of file TypeMapping.cpp.

◆ convert() [23/26]

MyRegion convert ( const visionx::types::Region &  region)

Converts a VisionX MyRegion object into an IVT MyRegion instance.

@parma region VisionX MyRegion object

Returns
IVT MyRegion instance

Definition at line 478 of file TypeMapping.cpp.

+ Here is the call graph for this function:

◆ convert() [24/26]

Transformation3d convert ( const visionx::types::Transformation3d &  transformation3d)

Converts a VisionX Transformation3d object into an IVT Transformation3d object.

@parma transformation3d VisionX Transformation3d object

Returns
IVT Transformation3d instance

Definition at line 533 of file TypeMapping.cpp.

+ Here is the call graph for this function:

◆ convert() [25/26]

Vec3d convert ( const visionx::types::Vec &  vec)

Converts a VisionX Vector (float STL Vector) into an IVT Vec3d.

Parameters
vecVisionX vector reference
Returns
IVT 3D Vector

Definition at line 219 of file TypeMapping.cpp.

◆ convert() [26/26]

Vec2d convert ( const visionx::types::Vec *  pVec)

Converts a VisionX Vector (float STL Vector) into an IVT Vec2d.

Parameters
vecVisionX vector pointer!
Returns
IVT 2D Vector

Definition at line 209 of file TypeMapping.cpp.

◆ convertEigenMatToVisionX()

visionx::types::Mat convertEigenMatToVisionX ( Eigen::MatrixXf  m)

Definition at line 667 of file TypeMapping.cpp.

+ Here is the call graph for this function:
+ Here is the caller graph for this function:

◆ convertEigenVecToVisionX()

visionx::types::Vec convertEigenVecToVisionX ( Eigen::VectorXf  v)

Definition at line 655 of file TypeMapping.cpp.

+ Here is the call graph for this function:
+ Here is the caller graph for this function:

◆ convertFromPCL() [1/12]

void visionx::tools::convertFromPCL ( const pcl::PointCloud< pcl::PointXYZRGBA >::Ptr  sourcePtr,
ColoredPointCloud &  target 
)

Definition at line 316 of file PointCloudConversions.cpp.

+ Here is the call graph for this function:

◆ convertFromPCL() [2/12]

void visionx::tools::convertFromPCL ( const pcl::PointCloud< pcl::PointXYZRGBA >::Ptr  sourcePtr,
visionx::ColoredPointCloud &  target 
)

◆ convertFromPCL() [3/12]

void visionx::tools::convertFromPCL ( const pcl::PointCloud< pcl::PointXYZRGBL > &  source,
ColoredLabeledPointCloud &  target 
)

Definition at line 354 of file PointCloudConversions.cpp.

+ Here is the call graph for this function:

◆ convertFromPCL() [4/12]

std::vector< VisionXPointT > convertFromPCL ( const pcl::PointCloud< PclPointT > &  source)

Convert a PCL point cloud to a VisionX point cloud (as return value).

Pass the desired point type as first template argument, for example:

pcl::PointCloud<pcl::PointXYZRGBA> source = ...;
ColoredPointCloud target = visionx::tools::convertFromPCL<ColoredPoint3D>(source);
ColoredPointCloud target = visionx::tools::convertFromPCL<ColoredPointCloud::value_type>(source);

Definition at line 245 of file PointCloudConversions.h.

+ Here is the call graph for this function:

◆ convertFromPCL() [5/12]

void convertFromPCL ( const pcl::PointCloud< PclPointT > &  source,
std::vector< VisionXPointT > &  target 
)

Convert a PCL point cloud to a VisionX point cloud.

Definition at line 233 of file PointCloudConversions.h.

+ Here is the call graph for this function:

◆ convertFromPCL() [6/12]

void convertFromPCL ( pcl::PointCloud< pcl::PointXYZ >::Ptr  sourcePtr,
void **  target 
)
Parameters
sourcePtrpoint to the source pcl point cloud

Definition at line 268 of file PointCloudConversions.cpp.

+ Here is the call graph for this function:

◆ convertFromPCL() [7/12]

void convertFromPCL ( pcl::PointCloud< pcl::PointXYZI >::Ptr  sourcePtr,
void **  target 
)

Definition at line 232 of file PointCloudConversions.cpp.

+ Here is the call graph for this function:

◆ convertFromPCL() [8/12]

void convertFromPCL ( pcl::PointCloud< pcl::PointXYZL >::Ptr  sourcePtr,
void **  target 
)

Definition at line 196 of file PointCloudConversions.cpp.

+ Here is the call graph for this function:

◆ convertFromPCL() [9/12]

void convertFromPCL ( pcl::PointCloud< pcl::PointXYZRGB >::Ptr  sourcePtr,
void **  target 
)

Definition at line 471 of file PointCloudConversions.cpp.

+ Here is the call graph for this function:

◆ convertFromPCL() [10/12]

void convertFromPCL ( pcl::PointCloud< pcl::PointXYZRGBA >::Ptr  sourcePtr,
void **  target 
)

Definition at line 121 of file PointCloudConversions.cpp.

+ Here is the call graph for this function:
+ Here is the caller graph for this function:

◆ convertFromPCL() [11/12]

void convertFromPCL ( pcl::PointCloud< pcl::PointXYZRGBL >::Ptr  sourcePtr,
void **  target 
)

Definition at line 333 of file PointCloudConversions.cpp.

+ Here is the call graph for this function:

◆ convertFromPCL() [12/12]

void convertFromPCL ( pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr &  sourcePtr,
void **  target 
)

Definition at line 429 of file PointCloudConversions.cpp.

+ Here is the call graph for this function:

◆ convertFromPCLToDebugDrawer() [1/4]

void convertFromPCLToDebugDrawer ( const pcl::PointCloud< pcl::PointXYZ >::Ptr &  sourcePtr,
armarx::DebugDrawer24BitColoredPointCloud &  target,
PCLToDebugDrawerConversionMode  mode,
float  pointSize 
)

Definition at line 611 of file PointCloudConversions.cpp.

+ Here is the call graph for this function:

◆ convertFromPCLToDebugDrawer() [2/4]

void convertFromPCLToDebugDrawer ( const pcl::PointCloud< pcl::PointXYZL >::Ptr &  sourcePtr,
armarx::DebugDrawer24BitColoredPointCloud &  target,
PCLToDebugDrawerConversionMode  mode,
float  pointSize 
)

Definition at line 567 of file PointCloudConversions.cpp.

+ Here is the call graph for this function:

◆ convertFromPCLToDebugDrawer() [3/4]

void convertFromPCLToDebugDrawer ( const pcl::PointCloud< pcl::PointXYZRGBA >::Ptr &  sourcePtr,
armarx::DebugDrawer24BitColoredPointCloud &  target,
PCLToDebugDrawerConversionMode  mode,
float  pointSize 
)

Definition at line 530 of file PointCloudConversions.cpp.

+ Here is the call graph for this function:
+ Here is the caller graph for this function:

◆ convertFromPCLToDebugDrawer() [4/4]

void convertFromPCLToDebugDrawer ( const pcl::PointCloud< pcl::PointXYZRGBL >::Ptr &  sourcePtr,
armarx::DebugDrawer24BitColoredPointCloud &  target,
PCLToDebugDrawerConversionMode  mode,
float  pointSize 
)

Definition at line 644 of file PointCloudConversions.cpp.

+ Here is the call graph for this function:

◆ convertImage() [1/2]

void visionx::tools::convertImage ( const ImageFormatInfo &  imageFormat,
const ImageType  destinationImageType,
void *  inputData,
void *  outputData 
)

This converts the input image data into a desired destination image data type specified in the given ImageProviderInfo.

If source image type equals destination image type, the image is simply copied, otherwise the image is converted if the conversion type is supported.

Supported conversions:

  • BayerPattern-{bg,gb,gr,rg} to BayerPattern-{bg,gb,gr,rg} (copy only)
  • BayerPattern-{bg,gb,gr,rg} to GrayScale
  • BayerPattern-{bg,gb,gr,rg} to RGB
  • GrayScale to GrayScale (copy only)
  • GrayScale to RGB
  • RGB to GrayScale
  • RGB to RGB (copy only)
  • Float single channel to Float single channel (copy only)
  • Float multiple channel to Float multiple channel (copy only)
Parameters
ImageFormatInfoImage format information which contains the source image type, source image size and more details needed for conversions.
destinationTypedestination image type of outputData
inputDatainput data array
outputDataoutput data array
Exceptions
visionx::UnsupportedImageConversionif conversion from a specific source type into a destination type is not supported or implemented.
+ Here is the caller graph for this function:

◆ convertImage() [2/2]

void convertImage ( const ImageProviderInfo imageProviderInfo,
void *  inputData,
void *  outputData 
)

Simplifies usage of visionx::tools:convertImage in ImageProcessors.

See also
visionx::tools::convertImage(const ImageFormatInfo&, const ImageType, unsigned char*, unsigned char*)
Parameters
ImageProviderInfoRegistered image provider information which contains the source image type, destination image type, source image size and more details needed for conversions.
inputDatainput data array
outputDataoutput data array
Exceptions
visionx::UnsupportedImageConversionif conversion from a specific source type into a destination type is not supported or implemented.

Definition at line 166 of file ImageUtil.cpp.

+ Here is the call graph for this function:

◆ convertIVTtoEigen() [1/2]

Eigen::Matrix3f convertIVTtoEigen ( const Mat3d  m)

Definition at line 632 of file TypeMapping.cpp.

+ Here is the caller graph for this function:

◆ convertIVTtoEigen() [2/2]

Eigen::Vector3f convertIVTtoEigen ( const Vec3d  v)

Definition at line 648 of file TypeMapping.cpp.

+ Here is the call graph for this function:

◆ convertPointFromPCL() [1/5]

void convertPointFromPCL ( const pcl::PointXYZ &  source,
visionx::Point3D &  target 
)

Definition at line 697 of file PointCloudConversions.cpp.

+ Here is the call graph for this function:
+ Here is the caller graph for this function:

◆ convertPointFromPCL() [2/5]

void convertPointFromPCL ( const pcl::PointXYZL &  source,
visionx::LabeledPoint3D &  target 
)

Definition at line 723 of file PointCloudConversions.cpp.

+ Here is the call graph for this function:

◆ convertPointFromPCL() [3/5]

void convertPointFromPCL ( const pcl::PointXYZRGBA &  source,
visionx::ColoredPoint3D &  target 
)

Definition at line 709 of file PointCloudConversions.cpp.

+ Here is the call graph for this function:

◆ convertPointFromPCL() [4/5]

void convertPointFromPCL ( const pcl::PointXYZRGBL &  source,
visionx::ColoredLabeledPoint3D &  target 
)

Definition at line 737 of file PointCloudConversions.cpp.

+ Here is the call graph for this function:

◆ convertPointFromPCL() [5/5]

void visionx::tools::convertPointFromPCL ( const PclPointT &  p,
VisionXPointT &  v 
)

Convert a PCL point type to a VisionX point type.

Definition at line 162 of file PointCloudConversions.h.

+ Here is the call graph for this function:

◆ convertPointToPCL() [1/5]

void convertPointToPCL ( const visionx::ColoredLabeledPoint3D &  source,
pcl::PointXYZRGBL &  target 
)

Definition at line 745 of file PointCloudConversions.cpp.

+ Here is the call graph for this function:

◆ convertPointToPCL() [2/5]

void convertPointToPCL ( const visionx::ColoredPoint3D &  source,
pcl::PointXYZRGBA &  target 
)

Definition at line 715 of file PointCloudConversions.cpp.

+ Here is the call graph for this function:

◆ convertPointToPCL() [3/5]

void convertPointToPCL ( const visionx::LabeledPoint3D &  source,
pcl::PointXYZL &  target 
)

Definition at line 729 of file PointCloudConversions.cpp.

+ Here is the call graph for this function:

◆ convertPointToPCL() [4/5]

void convertPointToPCL ( const visionx::Point3D &  source,
pcl::PointXYZ &  target 
)

Definition at line 702 of file PointCloudConversions.cpp.

+ Here is the call graph for this function:
+ Here is the caller graph for this function:

◆ convertPointToPCL() [5/5]

void visionx::tools::convertPointToPCL ( const VisionXPointT &  v,
PclPointT &  p 
)

Convert a VisionX point type to a PCL point type.

Definition at line 169 of file PointCloudConversions.h.

+ Here is the call graph for this function:

◆ convertToPCL() [1/12]

void visionx::tools::convertToPCL ( const ColoredLabeledPointCloud &  source,
pcl::PointCloud< pcl::PointXYZRGBL > &  target 
)

Definition at line 368 of file PointCloudConversions.cpp.

+ Here is the call graph for this function:

◆ convertToPCL() [2/12]

void visionx::tools::convertToPCL ( const ColoredPointCloud &  source,
pcl::PointCloud< pcl::PointXYZRGBA >::Ptr  targetPtr 
)

Definition at line 300 of file PointCloudConversions.cpp.

+ Here is the call graph for this function:

◆ convertToPCL() [3/12]

pcl::PointCloud< PclPointT >::Ptr convertToPCL ( const std::vector< VisionXPointT > &  source)

Convert a VisionX point cloud to a PCL point cloud (as return value).

Convert a VisionX point cloud to a PCL point cloud.

Pass the desired point type as first template argument, for example:

using PointCloudT = pcl::PointCloud<pcl::PointXYZRGBA>;
ColoredPointCloud source = ...;
pcl::PointCloud<pcl::PointXYZRGBA>::Ptr target = visionx::tools::convertToPCL<pcl::PointXYZRGBA>(source);
pcl::PointCloud<pcl::PointXYZRGBA> target = *visionx::tools::convertToPCL<PointCloudT::PointType>(source);

Definition at line 266 of file PointCloudConversions.h.

+ Here is the call graph for this function:

◆ convertToPCL() [4/12]

void convertToPCL ( const std::vector< VisionXPointT > &  source,
pcl::PointCloud< PclPointT > &  target 
)

Convert a VisionX point cloud to a PCL point cloud.

Definition at line 254 of file PointCloudConversions.h.

+ Here is the call graph for this function:

◆ convertToPCL() [5/12]

void visionx::tools::convertToPCL ( const visionx::ColoredPointCloud &  source,
pcl::PointCloud< pcl::PointXYZRGBA >::Ptr  targetPtr 
)

◆ convertToPCL() [6/12]

void convertToPCL ( void **  source,
visionx::MetaPointCloudFormatPtr  pointCloudFormat,
pcl::PointCloud< pcl::PointXYZ >::Ptr  targetPtr 
)
Parameters
targetPtrpoint to the pcl point cloud

Definition at line 285 of file PointCloudConversions.cpp.

+ Here is the call graph for this function:

◆ convertToPCL() [7/12]

void convertToPCL ( void **  source,
visionx::MetaPointCloudFormatPtr  pointCloudFormat,
pcl::PointCloud< pcl::PointXYZI >::Ptr  targetPtr 
)

Definition at line 250 of file PointCloudConversions.cpp.

+ Here is the call graph for this function:

◆ convertToPCL() [8/12]

void convertToPCL ( void **  source,
visionx::MetaPointCloudFormatPtr  pointCloudFormat,
pcl::PointCloud< pcl::PointXYZL >::Ptr  targetPtr 
)

Definition at line 214 of file PointCloudConversions.cpp.

+ Here is the call graph for this function:

◆ convertToPCL() [9/12]

void convertToPCL ( void **  source,
visionx::MetaPointCloudFormatPtr  pointCloudFormat,
pcl::PointCloud< pcl::PointXYZRGB >::Ptr  targetPtr 
)

Definition at line 496 of file PointCloudConversions.cpp.

+ Here is the call graph for this function:

◆ convertToPCL() [10/12]

void convertToPCL ( void **  source,
visionx::MetaPointCloudFormatPtr  pointCloudFormat,
pcl::PointCloud< pcl::PointXYZRGBA >::Ptr  targetPtr 
)

Definition at line 146 of file PointCloudConversions.cpp.

+ Here is the call graph for this function:
+ Here is the caller graph for this function:

◆ convertToPCL() [11/12]

void convertToPCL ( void **  source,
visionx::MetaPointCloudFormatPtr  pointCloudFormat,
pcl::PointCloud< pcl::PointXYZRGBL >::Ptr  targetPtr 
)

Definition at line 389 of file PointCloudConversions.cpp.

+ Here is the call graph for this function:

◆ convertToPCL() [12/12]

void convertToPCL ( void **  source,
visionx::MetaPointCloudFormatPtr  pointCloudFormat,
pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr  targetPtr 
)

Definition at line 450 of file PointCloudConversions.cpp.

+ Here is the call graph for this function:

◆ createByteImage() [1/3]

CByteImage * createByteImage ( const ImageFormatInfo &  imageFormat)

Definition at line 195 of file ImageUtil.cpp.

+ Here is the call graph for this function:

◆ createByteImage() [2/3]

CByteImage* visionx::tools::createByteImage ( const ImageFormatInfo &  imageFormat,
const ImageType  imageType 
)

Creates a ByteImage for the destination type specified in the given imageProviderInfo.

Parameters
ImageFormatInfoImage format information which contains the source image size
imageTypeRequired VisionX image type which will be mapped onto an appropriate CByteImage::ImageType
Returns
Appropriate CByteImage
+ Here is the caller graph for this function:

◆ createByteImage() [3/3]

CByteImage * createByteImage ( const ImageProviderInfo imageProviderInfo)

Simplifies usage of visionx::tools:convertImage in ImageProcessors.

See also
visionx::tools::createImage(const ImageFormatInfo&, const ImageType)
Parameters
imageProviderInfoRegistered image provider information which contains the ImageFormatInfo and destination image type.
Returns
CByteImage Appropriate CByteImage

Definition at line 201 of file ImageUtil.cpp.

+ Here is the call graph for this function:

◆ createDefaultMonocularCalibration()

visionx::MonocularCalibration createDefaultMonocularCalibration ( )

Creates a MonocularCalibration with all parameters set to a neutral value.

Definition at line 237 of file ImageUtil.cpp.

+ Here is the caller graph for this function:

◆ createFloatImage() [1/2]

CFloatImage* visionx::tools::createFloatImage ( const ImageFormatInfo &  imageFormat,
const ImageType  imageType 
)

Creates a FloatImage for the destination type specified in the given imageProviderInfo.

Parameters
ImageFormatInfoImage format information which contains the source image size
imageTypeRequired VisionX image type which will be mapped onto an appropriate number of channels
Returns
CByteImage Appropriate CFloatImage
+ Here is the caller graph for this function:

◆ createFloatImage() [2/2]

CFloatImage * createFloatImage ( const ImageProviderInfo imageProviderInfo)

Simplifies usage of visionx::tools:convertImage in ImageProcessors.

See also
visionx::tools::createFloatImage(const ImageFormatInfo&, const ImageType)
Parameters
imageProviderInfoRegistered image provider information which contains the ImageFormatInfo and destination image type.
Returns
CByteImage Appropriate CFloatImage

Definition at line 231 of file ImageUtil.cpp.

+ Here is the call graph for this function:

◆ DECLARE_fitPlaneRansac_PointT() [1/4]

visionx::tools::DECLARE_fitPlaneRansac_PointT ( pcl::PointXYZ  )

◆ DECLARE_fitPlaneRansac_PointT() [2/4]

visionx::tools::DECLARE_fitPlaneRansac_PointT ( pcl::PointXYZRGB  )

◆ DECLARE_fitPlaneRansac_PointT() [3/4]

visionx::tools::DECLARE_fitPlaneRansac_PointT ( pcl::PointXYZRGBA  )

◆ DECLARE_fitPlaneRansac_PointT() [4/4]

visionx::tools::DECLARE_fitPlaneRansac_PointT ( pcl::PointXYZRGBL  )

◆ depthValueToRGB()

void visionx::tools::depthValueToRGB ( unsigned int  depthInMM,
unsigned char &  r,
unsigned char &  g,
unsigned char &  b,
bool  noiseResistant = false 
)
inline

Definition at line 176 of file ImageUtil.h.

+ Here is the call graph for this function:
+ Here is the caller graph for this function:

◆ downsampleByVoxelGrid() [1/2]

PointCloudT::Ptr visionx::tools::downsampleByVoxelGrid ( typename PointCloudT::ConstPtr  inputCloud,
float  leafSize = 5.0,
pcl::IndicesConstPtr  indices = nullptr 
)

Definition at line 40 of file downsampling_voxelgrid.hpp.

+ Here is the call graph for this function:

◆ downsampleByVoxelGrid() [2/2]

PointCloudT::Ptr visionx::tools::downsampleByVoxelGrid ( typename PointCloudT::ConstPtr  inputCloud,
float  leafSize = 5.0,
pcl::PointIndicesConstPtr  indices = nullptr 
)

Definition at line 47 of file downsampling_voxelgrid.hpp.

+ Here is the call graph for this function:

◆ fillLabelMap() [1/2]

std::enable_if<!is_shared_ptr<PointCloudT>::value, void>::type visionx::tools::fillLabelMap ( const PointCloudT &  labeledCloud,
std::map< uint32_t, pcl::PointIndices > &  labelIndicesMap,
bool  excludeZero = true 
)
See also
detail::fillLabelMap()

Definition at line 135 of file PCLUtilities.h.

+ Here is the call graph for this function:

◆ fillLabelMap() [2/2]

std::enable_if<is_shared_ptr<LabeledPointCloudPtrT>::value, void>::type visionx::tools::fillLabelMap ( LabeledPointCloudPtrT  labeledCloudPtr,
std::map< uint32_t, pcl::PointIndices > &  labelIndicesMap,
bool  excludeZero = true 
)
See also
detail::fillLabelMap()

Definition at line 124 of file PCLUtilities.h.

+ Here is the call graph for this function:

◆ fitPlaneRansac()

std::optional<PlaneFittingResult> visionx::tools::fitPlaneRansac ( typename pcl::PointCloud< PointT >::Ptr  cloud,
double  distanceThreshold = 1.0,
const IndicesPtrT &  indices = nullptr 
)

Definition at line 17 of file plane_fitting_ransac.hpp.

+ Here is the call graph for this function:

◆ getAABB() [1/2]

simox::AxisAlignedBoundingBox visionx::tools::getAABB ( const PointCloudT &  pointCloud,
const pcl::PointIndices &  indices = {} 
)

Get the axis-aligned bounding-box of the given point cloud.

Parameters
pointCloudThe point cloud.
indicesIf not empty, only the specified point indices are used.
Returns
The AABB in a 3x2 matrix, where with min's in col(0) and max'x in col(1).

Definition at line 27 of file AABB.h.

+ Here is the caller graph for this function:

◆ getAABB() [2/2]

simox::AxisAlignedBoundingBox visionx::tools::getAABB ( const PointCloudT &  pointCloud,
const pcl::PointIndices::Ptr &  indices 
)

Definition at line 55 of file AABB.h.

+ Here is the call graph for this function:

◆ getBytesPerPoint()

size_t getBytesPerPoint ( visionx::PointContentType  pointContent)

Definition at line 64 of file PointCloudConversions.cpp.

+ Here is the caller graph for this function:

◆ getCropIndices()

pcl::PointIndices::Ptr visionx::tools::getCropIndices ( const PointCloudT &  inputCloud,
Eigen::Vector3f  min,
Eigen::Vector3f  max 
)

Definition at line 16 of file crop.h.

+ Here is the call graph for this function:
+ Here is the caller graph for this function:

◆ getCropped()

PointCloudT::Ptr visionx::tools::getCropped ( const PointCloudT &  inputCloud,
Eigen::Vector3f  min,
Eigen::Vector3f  max 
)

Definition at line 36 of file crop.h.

+ Here is the call graph for this function:

◆ getHardwareId()

std::string visionx::tools::getHardwareId ( )

Retrieve hardware id to identify local machine.

This method generates a hardware id from the mac address.

Returns
hardware id

◆ getLabelMap()

std::map<uint32_t, pcl::PointIndices> visionx::tools::getLabelMap ( const PointCloudT &  labeledCloud,
bool  excludeZero = true 
)
See also
detail::fillLabelMap()

Definition at line 144 of file PCLUtilities.h.

+ Here is the call graph for this function:
+ Here is the caller graph for this function:

◆ getLabelSet() [1/2]

std::set<uint32_t> visionx::tools::getLabelSet ( const pcl::PointCloud< LabeledPointT > &  pointCloud)

Return the set of labels in pointCloud.

Definition at line 96 of file segments.h.

◆ getLabelSet() [2/2]

std::set<uint32_t> visionx::tools::getLabelSet ( const std::map< uint32_t, ValueT > &  segmentIndices)

Return the labels in segmentIndices as std::set.

Definition at line 108 of file segments.h.

◆ getPointContentType()

visionx::PointContentType visionx::tools::getPointContentType ( )

Definition at line 41 of file PointCloudConversions.h.

◆ getPointContentType< pcl::PointNormal >()

visionx::PointContentType getPointContentType< pcl::PointNormal > ( )

Definition at line 46 of file PointCloudConversions.cpp.

◆ getPointContentType< pcl::PointXYZ >()

visionx::PointContentType getPointContentType< pcl::PointXYZ > ( )

Definition at line 33 of file PointCloudConversions.cpp.

◆ getPointContentType< pcl::PointXYZI >()

visionx::PointContentType getPointContentType< pcl::PointXYZI > ( )

Definition at line 41 of file PointCloudConversions.cpp.

◆ getPointContentType< pcl::PointXYZL >()

visionx::PointContentType getPointContentType< pcl::PointXYZL > ( )

Definition at line 37 of file PointCloudConversions.cpp.

◆ getPointContentType< pcl::PointXYZRGBA >()

visionx::PointContentType getPointContentType< pcl::PointXYZRGBA > ( )

Definition at line 50 of file PointCloudConversions.cpp.

◆ getPointContentType< pcl::PointXYZRGBL >()

visionx::PointContentType getPointContentType< pcl::PointXYZRGBL > ( )

Definition at line 54 of file PointCloudConversions.cpp.

◆ getPointContentType< pcl::PointXYZRGBNormal >()

visionx::PointContentType getPointContentType< pcl::PointXYZRGBNormal > ( )

Definition at line 58 of file PointCloudConversions.cpp.

◆ getSegmentAABBs() [1/2]

std::map<uint32_t, simox::AxisAlignedBoundingBox> visionx::tools::getSegmentAABBs ( const pcl::PointCloud< PointT > &  pointCloud,
const std::map< uint32_t, IndicesT > &  segmentIndices 
)

Definition at line 175 of file segments.h.

+ Here is the call graph for this function:

◆ getSegmentAABBs() [2/2]

std::vector<simox::AxisAlignedBoundingBox> visionx::tools::getSegmentAABBs ( const pcl::PointCloud< PointT > &  pointCloud,
const std::vector< IndicesT > &  segmentIndices 
)

Definition at line 161 of file segments.h.

+ Here is the call graph for this function:
+ Here is the caller graph for this function:

◆ getSegmentIndices()

std::map<uint32_t, pcl::PointIndices> visionx::tools::getSegmentIndices ( const pcl::PointCloud< LabeledPointT > &  labeledCloud,
bool  excludeZero = false 
)

Get a map from segment labels to indices of segments' points.

Parameters
labeledCloudA labeled point cloud.
excludeZeroIf true, points with label == 0 are ignored.
Returns
Map from segment labels to segment indices.

Definition at line 74 of file segments.h.

+ Here is the call graph for this function:

◆ getSegmentIndicesPtr()

std::map<uint32_t, pcl::PointIndices::Ptr> visionx::tools::getSegmentIndicesPtr ( const pcl::PointCloud< LabeledPointT > &  labeledCloud,
bool  excludeZero = false 
)

Version of addSegmentIndices() containing pcl::PointIndices::Ptr.

See also
addSegmentIndices()

Definition at line 85 of file segments.h.

+ Here is the call graph for this function:

◆ getUniqueLabels()

std::vector<uint32_t> visionx::tools::getUniqueLabels ( const std::map< uint32_t, ValueT > &  segmentIndices)

Return the labels in segmentIndices as std::vector.

Definition at line 120 of file segments.h.

◆ imageTypeToTypeName()

std::string imageTypeToTypeName ( const ImageType  imageType)

Converts an image type into a string integer.

Parameters
imageTypeImage type
Returns
Type name string

Definition at line 70 of file TypeMapping.cpp.

+ Here is the caller graph for this function:

◆ isColored() [1/2]

bool visionx::tools::isColored ( PointContentType  type)

Definition at line 95 of file PointCloudConversions.cpp.

◆ isColored() [2/2]

bool visionx::tools::isColored ( visionx::PointContentType  type)

Indicate whether this point type contains colors.

◆ isLabeled() [1/2]

bool visionx::tools::isLabeled ( PointContentType  type)

Definition at line 108 of file PointCloudConversions.cpp.

+ Here is the caller graph for this function:

◆ isLabeled() [2/2]

bool visionx::tools::isLabeled ( visionx::PointContentType  type)

Indicate whether this point type contains labels.

◆ relabel() [1/2]

void visionx::tools::relabel ( pcl::PointCloud< PointT > &  pointCloud,
const std::map< uint32_t, pcl::PointIndices > &  segmentIndices 
)

Definition at line 133 of file segments.h.

+ Here is the call graph for this function:

◆ relabel() [2/2]

void visionx::tools::relabel ( pcl::PointCloud< PointT > &  pointCloud,
const std::map< uint32_t, pcl::PointIndices::Ptr > &  segmentIndices 
)

Definition at line 146 of file segments.h.

+ Here is the call graph for this function:

◆ rgbToDepthValue()

float visionx::tools::rgbToDepthValue ( unsigned char  r,
unsigned char  g,
unsigned char  b,
bool  noiseResistant = false 
)
inline

Definition at line 142 of file ImageUtil.h.

+ Here is the call graph for this function:
+ Here is the caller graph for this function:

◆ toAABB()

simox::AxisAlignedBoundingBox toAABB ( const BoundingBox3D &  boundingBox)

Definition at line 23 of file AABB.cpp.

◆ toBoundingBox3D() [1/2]

BoundingBox3D toBoundingBox3D ( const Eigen::Vector3f &  min,
const Eigen::Vector3f &  max 
)

Definition at line 6 of file AABB.cpp.

+ Here is the call graph for this function:
+ Here is the caller graph for this function:

◆ toBoundingBox3D() [2/2]

BoundingBox3D toBoundingBox3D ( const simox::AxisAlignedBoundingBox &  aabb)

Definition at line 18 of file AABB.cpp.

+ Here is the call graph for this function:

◆ toString() [1/2]

std::string visionx::tools::toString ( PointContentType  pointContent)

Definition at line 765 of file PointCloudConversions.cpp.

+ Here is the caller graph for this function:

◆ toString() [2/2]

std::string visionx::tools::toString ( visionx::PointContentType  pointContent)

◆ typeNameToImageType()

visionx::ImageType typeNameToImageType ( const std::string &  imageTypeName)

Converts an image type name as string into an ImageType integer.

Parameters
imageTypeNameImage type string
Returns
VisionX::ImageType if the image type name is valid

Definition at line 42 of file TypeMapping.cpp.

+ Here is the call graph for this function:
+ Here is the caller graph for this function:

◆ vectorToArray()

T* visionx::tools::vectorToArray ( const std::vector< T > &  dataVector)

Definition at line 60 of file TypeMapping.h.

+ Here is the caller graph for this function:
boost::target
Vertex target(const detail::edge_base< Directed, Vertex > &e, const PCG &)
Definition: point_cloud_graph.h:688
visionx::tools::callWithPointType
std::enable_if_t< !std::is_base_of< detail::FunctorWithReturnType, FunctorT >::value, void > callWithPointType(FunctorT &functor, PointContentType type, Args... args)
Call functor with the correct pcl point type according to type.
Definition: call_with_point_type.h:104
visionx::tools::FunctorWithReturnType
Base class for functors with return value.
Definition: call_with_point_type.h:62
armarx::PointCloudT
pcl::PointCloud< PointT > PointCloudT
Definition: Common.h:30
boost::source
Vertex source(const detail::edge_base< Directed, Vertex > &e, const PCG &)
Definition: point_cloud_graph.h:681
visionx::tools::getPointContentType
visionx::PointContentType getPointContentType()
Definition: PointCloudConversions.h:41