|
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 ®ion) |
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) |
Eigen::MatrixXf | convertVisionXMatToEigen (visionx::types::Mat m) |
Eigen::VectorXf | convertVisionXVecToEigen (visionx::types::Vec v) |
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< PlaneFittingResult > | fitPlaneRansac (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 > | |
T * | vectorToArray (const std::vector< T > &dataVector) |
Enumerator | |
---|---|
eConvertAsPoints | |
eConvertAsColors | |
eConvertAsLabels |
Definition at line 102 of file PointCloudConversions.h.
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
.
segmentIndices | The map to fill (label -> point indicies). |
labeledCloud | A labeled point cloud. |
excludeZero | If true, points with label == 0 are ignored. |
Definition at line 52 of file segments.h.
void visionx::tools::addSegmentIndices | ( | std::map< uint32_t, pcl::PointIndices::Ptr > & | segmentIndices, |
const pcl::PointCloud< LabeledPointT > & | labeledCloud, | ||
bool | excludeZero = false |
||
) |
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.
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(); }
function | The function to be called. |
type | The point content type. |
args | Optional additional arguments passed to the called function. |
Definition at line 279 of file call_with_point_type.h.
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.
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(); }
function | The function to be called. |
type | The point content type. |
args | Optional additional arguments passed to the called function. |
Definition at line 303 of file call_with_point_type.h.
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.
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.
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:
Construct your functor and pass it to callWithPointType()
along with the respective PointContentType
:
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()
:
Usage:
If your functor returns a result, have it derive from FunctorWithReturnType
, specifying the return type as template argument:
Usage:
functor | The functor to be called. |
type | The point content type. |
args | Arguments passed to functor call. |
Definition at line 104 of file call_with_point_type.h.
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.
|
inline |
Definition at line 65 of file PCLUtilities.h.
std::tuple<uint8_t, uint8_t, uint8_t> visionx::tools::colorizeSegment | ( | PointCloudPtrT & | segment | ) |
ImageProcessor::BayerPatternType convert | ( | const BayerPatternType | visionxBayerPatternType | ) |
Converts a VisionX BayerPatternType into a IVT's image processor BayerPatternType.
visionxBayerPatternType | VisionX Bayer pattern type |
Definition at line 118 of file TypeMapping.cpp.
visionx::MonocularCalibration convert | ( | const CCalibration & | ivtCalibration | ) |
Converts an IVT CCalibration into a VisionX MonocularCalibration struct.
ivtCalibration | IVT Calibration |
Definition at line 436 of file TypeMapping.cpp.
visionx::StereoCalibration convert | ( | const CStereoCalibration & | ivtStereoCalibration | ) |
Converts an IVT CStereoCalibration into a VisionX StereoCalibration struct.
ivtStereoCalibration | IVT StereoCalibration |
Definition at line 391 of file TypeMapping.cpp.
CVideoCaptureInterface::FrameRate convert | ( | const float | frameRate | ) |
Converts frame rate floats into distinct IVT FrameRates by applying quantization.
frameRate | frame rate |
Definition at line 175 of file TypeMapping.cpp.
CVideoCaptureInterface::VideoMode convert | ( | const ImageDimension & | imageDimension | ) |
Converts a VisionX image dimension object into an IVT VideoMode of IVT's CVideoCaptureInterface.
imageDimension | VisionX image dimension which consist of image width and height |
Definition at line 141 of file TypeMapping.cpp.
CByteImage::ImageType convert | ( | const ImageType | visionxImageType | ) |
Converts a VisionX image type into an image type of IVT's ByteImage.
visionXImageType | VisionX image type |
Definition at line 95 of file TypeMapping.cpp.
visionx::types::Mat convert | ( | const Mat3d & | mat | ) |
Converts an IVT Mat3d into VisionX Matrix (float STL Vectors)
vec | IVT 3D Matrix |
Definition at line 274 of file TypeMapping.cpp.
visionx::types::Region convert | ( | const MyRegion & | ivtRegion | ) |
Converts an IVT MyRegion into a VisionX MyRegion.
ivtRegion | IVT MyRegion struct instance |
Definition at line 458 of file TypeMapping.cpp.
visionx::types::Object3DEntry convert | ( | const Object3DEntry & | ivtObject3DEntry | ) |
Converts an IVT Object3DEntry id into a VisionX ObjectEntry.
ivtObject3DEntry | IVT Object3DEntry |
Definition at line 570 of file TypeMapping.cpp.
visionx::types::Object3DList convert | ( | const Object3DList & | ivtObject3DList | ) |
Converts an IVT Object3DList object into an VisionX ObjectList.
ivtObject3DList | IVT Object3DList instance |
Definition at line 613 of file TypeMapping.cpp.
visionx::types::ObjectColor convert | ( | const ObjectColor & | ivtObjectColor | ) |
Mapps an IVT Object color id onto a VisionX object color id.
ivtObjectColor | IVT Object color id |
Definition at line 498 of file TypeMapping.cpp.
visionx::types::ObjectType convert | ( | const ObjectType & | ivtObjectType | ) |
Mapps an IVT Object type id onto a VisionX object type id.
ivtObjectType | IVT Object type id |
Definition at line 510 of file TypeMapping.cpp.
visionx::types::Transformation3d convert | ( | const Transformation3d & | ivtTransformation3d | ) |
Converts an IVT Transformation3d into a VisionX Transformation3d.
ivtTransformation3d | IVT Transformation3d struct instance |
Definition at line 522 of file TypeMapping.cpp.
visionx::types::Vec convert | ( | const Vec2d & | vec | ) |
Converts an IVT Vec2d Vector into VisionX Vector (float STL Vector)
vec | IVT 2D Vector |
Definition at line 253 of file TypeMapping.cpp.
visionx::types::Vec convert | ( | const Vec3d & | vec | ) |
Converts an IVT Vec3d Vector into VisionX Vector (float STL Vector)
vec | IVT 3D Vector |
Definition at line 263 of file TypeMapping.cpp.
CCalibration * convert | ( | const visionx::MonocularCalibration & | calibration | ) |
Converts a VisionX MonocularCalibration object into an IVT CCalibration.
calibration | VisionX Stereo Calibration struct |
Definition at line 363 of file TypeMapping.cpp.
CStereoCalibration * convert | ( | const visionx::StereoCalibration & | stereoCalibration | ) |
Converts a VisionX StereoCalibration object into an IVT CStereoCalibration.
stereoCalibration | VisionX Stereo Calibration struct |
Definition at line 300 of file TypeMapping.cpp.
Mat3d convert | ( | const visionx::types::Mat & | mat | ) |
Converts a VisionX Matrix (float STL Vectors) into an IVT Mat3d.
vec | VisionX matrix |
Definition at line 230 of file TypeMapping.cpp.
Object3DEntry convert | ( | const visionx::types::Object3DEntry & | object3DEntry | ) |
Converts a VisionX ObjectEntry object into an IVT Object3DEntry instance.
objectEntry | VisionX ObjectEntry object |
Definition at line 544 of file TypeMapping.cpp.
Object3DList convert | ( | const visionx::types::Object3DList & | object3DList | ) |
Converts an IVT Object3DList object into a VisionX Object3DEntry instance.
objectList | VisionX Object3DEntry instance |
Definition at line 594 of file TypeMapping.cpp.
ObjectColor convert | ( | const visionx::types::ObjectColor & | objectColor | ) |
Mapps an IVT Object color id onto a VisionX object color id.
objectColor | VisionX object color id |
Definition at line 504 of file TypeMapping.cpp.
ObjectType convert | ( | const visionx::types::ObjectType & | objectType | ) |
Mapps an IVT Object type id onto a VisionX object type id.
objectType | VisionX object type id |
Definition at line 516 of file TypeMapping.cpp.
MyRegion convert | ( | const visionx::types::Region & | region | ) |
Converts a VisionX MyRegion object into an IVT MyRegion instance.
@parma region VisionX MyRegion object
Definition at line 478 of file TypeMapping.cpp.
Transformation3d convert | ( | const visionx::types::Transformation3d & | transformation3d | ) |
Converts a VisionX Transformation3d object into an IVT Transformation3d object.
@parma transformation3d VisionX Transformation3d object
Definition at line 533 of file TypeMapping.cpp.
Vec3d convert | ( | const visionx::types::Vec & | vec | ) |
Converts a VisionX Vector (float STL Vector) into an IVT Vec3d.
vec | VisionX vector reference |
Definition at line 219 of file TypeMapping.cpp.
Vec2d convert | ( | const visionx::types::Vec * | pVec | ) |
Converts a VisionX Vector (float STL Vector) into an IVT Vec2d.
vec | VisionX vector pointer! |
Definition at line 209 of file TypeMapping.cpp.
visionx::types::Mat convertEigenMatToVisionX | ( | Eigen::MatrixXf | m | ) |
Definition at line 677 of file TypeMapping.cpp.
visionx::types::Vec convertEigenVecToVisionX | ( | Eigen::VectorXf | v | ) |
Definition at line 655 of file TypeMapping.cpp.
void visionx::tools::convertFromPCL | ( | const pcl::PointCloud< pcl::PointXYZRGBA >::Ptr | sourcePtr, |
ColoredPointCloud & | target | ||
) |
void visionx::tools::convertFromPCL | ( | const pcl::PointCloud< pcl::PointXYZRGBA >::Ptr | sourcePtr, |
visionx::ColoredPointCloud & | target | ||
) |
void visionx::tools::convertFromPCL | ( | const pcl::PointCloud< pcl::PointXYZRGBL > & | source, |
ColoredLabeledPointCloud & | target | ||
) |
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:
Definition at line 245 of file PointCloudConversions.h.
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.
void convertFromPCL | ( | pcl::PointCloud< pcl::PointXYZ >::Ptr | sourcePtr, |
void ** | target | ||
) |
sourcePtr | point to the source pcl point cloud |
Definition at line 268 of file PointCloudConversions.cpp.
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 | ||
) |
Definition at line 121 of file PointCloudConversions.cpp.
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 | ||
) |
Definition at line 530 of file PointCloudConversions.cpp.
void convertFromPCLToDebugDrawer | ( | const pcl::PointCloud< pcl::PointXYZRGBL >::Ptr & | sourcePtr, |
armarx::DebugDrawer24BitColoredPointCloud & | target, | ||
PCLToDebugDrawerConversionMode | mode, | ||
float | pointSize | ||
) |
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:
ImageFormatInfo | Image format information which contains the source image type, source image size and more details needed for conversions. |
destinationType | destination image type of outputData |
inputData | input data array |
outputData | output data array |
visionx::UnsupportedImageConversion | if conversion from a specific source type into a destination type is not supported or implemented. |
void convertImage | ( | const ImageProviderInfo & | imageProviderInfo, |
void * | inputData, | ||
void * | outputData | ||
) |
Simplifies usage of visionx::tools:convertImage in ImageProcessors.
ImageProviderInfo | Registered image provider information which contains the source image type, destination image type, source image size and more details needed for conversions. |
inputData | input data array |
outputData | output data array |
visionx::UnsupportedImageConversion | if conversion from a specific source type into a destination type is not supported or implemented. |
Definition at line 166 of file ImageUtil.cpp.
Eigen::Matrix3f convertIVTtoEigen | ( | const Mat3d | m | ) |
Eigen::Vector3f convertIVTtoEigen | ( | const Vec3d | v | ) |
void convertPointFromPCL | ( | const pcl::PointXYZ & | source, |
visionx::Point3D & | target | ||
) |
Definition at line 697 of file PointCloudConversions.cpp.
void convertPointFromPCL | ( | const pcl::PointXYZL & | source, |
visionx::LabeledPoint3D & | target | ||
) |
void convertPointFromPCL | ( | const pcl::PointXYZRGBA & | source, |
visionx::ColoredPoint3D & | target | ||
) |
void convertPointFromPCL | ( | const pcl::PointXYZRGBL & | source, |
visionx::ColoredLabeledPoint3D & | target | ||
) |
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.
void convertPointToPCL | ( | const visionx::ColoredLabeledPoint3D & | source, |
pcl::PointXYZRGBL & | target | ||
) |
void convertPointToPCL | ( | const visionx::ColoredPoint3D & | source, |
pcl::PointXYZRGBA & | target | ||
) |
void convertPointToPCL | ( | const visionx::LabeledPoint3D & | source, |
pcl::PointXYZL & | target | ||
) |
void convertPointToPCL | ( | const visionx::Point3D & | source, |
pcl::PointXYZ & | target | ||
) |
Definition at line 702 of file PointCloudConversions.cpp.
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.
void visionx::tools::convertToPCL | ( | const ColoredLabeledPointCloud & | source, |
pcl::PointCloud< pcl::PointXYZRGBL > & | target | ||
) |
void visionx::tools::convertToPCL | ( | const ColoredPointCloud & | source, |
pcl::PointCloud< pcl::PointXYZRGBA >::Ptr | targetPtr | ||
) |
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:
Definition at line 266 of file PointCloudConversions.h.
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.
void visionx::tools::convertToPCL | ( | const visionx::ColoredPointCloud & | source, |
pcl::PointCloud< pcl::PointXYZRGBA >::Ptr | targetPtr | ||
) |
void convertToPCL | ( | void ** | source, |
visionx::MetaPointCloudFormatPtr | pointCloudFormat, | ||
pcl::PointCloud< pcl::PointXYZ >::Ptr | targetPtr | ||
) |
targetPtr | point to the pcl point cloud |
Definition at line 285 of file PointCloudConversions.cpp.
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 | ||
) |
Definition at line 146 of file PointCloudConversions.cpp.
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 | ||
) |
Eigen::MatrixXf convertVisionXMatToEigen | ( | visionx::types::Mat | m | ) |
Definition at line 691 of file TypeMapping.cpp.
Eigen::VectorXf convertVisionXVecToEigen | ( | visionx::types::Vec | v | ) |
Definition at line 666 of file TypeMapping.cpp.
CByteImage * createByteImage | ( | const ImageFormatInfo & | imageFormat | ) |
CByteImage* visionx::tools::createByteImage | ( | const ImageFormatInfo & | imageFormat, |
const ImageType | imageType | ||
) |
Creates a ByteImage for the destination type specified in the given imageProviderInfo.
ImageFormatInfo | Image format information which contains the source image size |
imageType | Required VisionX image type which will be mapped onto an appropriate CByteImage::ImageType |
CByteImage * createByteImage | ( | const ImageProviderInfo & | imageProviderInfo | ) |
Simplifies usage of visionx::tools:convertImage in ImageProcessors.
imageProviderInfo | Registered image provider information which contains the ImageFormatInfo and destination image type. |
Definition at line 201 of file ImageUtil.cpp.
visionx::MonocularCalibration createDefaultMonocularCalibration | ( | ) |
Creates a MonocularCalibration with all parameters set to a neutral value.
Definition at line 237 of file ImageUtil.cpp.
CFloatImage* visionx::tools::createFloatImage | ( | const ImageFormatInfo & | imageFormat, |
const ImageType | imageType | ||
) |
Creates a FloatImage for the destination type specified in the given imageProviderInfo.
ImageFormatInfo | Image format information which contains the source image size |
imageType | Required VisionX image type which will be mapped onto an appropriate number of channels |
CFloatImage * createFloatImage | ( | const ImageProviderInfo & | imageProviderInfo | ) |
Simplifies usage of visionx::tools:convertImage in ImageProcessors.
imageProviderInfo | Registered image provider information which contains the ImageFormatInfo and destination image type. |
Definition at line 231 of file ImageUtil.cpp.
visionx::tools::DECLARE_fitPlaneRansac_PointT | ( | pcl::PointXYZ | ) |
visionx::tools::DECLARE_fitPlaneRansac_PointT | ( | pcl::PointXYZRGB | ) |
visionx::tools::DECLARE_fitPlaneRansac_PointT | ( | pcl::PointXYZRGBA | ) |
visionx::tools::DECLARE_fitPlaneRansac_PointT | ( | pcl::PointXYZRGBL | ) |
|
inline |
Definition at line 176 of file ImageUtil.h.
PointCloudT::Ptr visionx::tools::downsampleByVoxelGrid | ( | typename PointCloudT::ConstPtr | inputCloud, |
float | leafSize = 5.0 , |
||
pcl::IndicesConstPtr | indices = nullptr |
||
) |
PointCloudT::Ptr visionx::tools::downsampleByVoxelGrid | ( | typename PointCloudT::ConstPtr | inputCloud, |
float | leafSize = 5.0 , |
||
pcl::PointIndicesConstPtr | indices = nullptr |
||
) |
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 |
||
) |
Definition at line 135 of file PCLUtilities.h.
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 |
||
) |
Definition at line 124 of file PCLUtilities.h.
std::optional<PlaneFittingResult> visionx::tools::fitPlaneRansac | ( | typename pcl::PointCloud< PointT >::Ptr | cloud, |
double | distanceThreshold = 1.0 , |
||
const IndicesPtrT & | indices = nullptr |
||
) |
simox::AxisAlignedBoundingBox visionx::tools::getAABB | ( | const PointCloudT & | pointCloud, |
const pcl::PointIndices & | indices = {} |
||
) |
Get the axis-aligned bounding-box of the given point cloud.
pointCloud | The point cloud. |
indices | If not empty, only the specified point indices are used. |
Definition at line 27 of file AABB.h.
simox::AxisAlignedBoundingBox visionx::tools::getAABB | ( | const PointCloudT & | pointCloud, |
const pcl::PointIndices::Ptr & | indices | ||
) |
size_t getBytesPerPoint | ( | visionx::PointContentType | pointContent | ) |
Definition at line 64 of file PointCloudConversions.cpp.
pcl::PointIndices::Ptr visionx::tools::getCropIndices | ( | const PointCloudT & | inputCloud, |
Eigen::Vector3f | min, | ||
Eigen::Vector3f | max | ||
) |
PointCloudT::Ptr visionx::tools::getCropped | ( | const PointCloudT & | inputCloud, |
Eigen::Vector3f | min, | ||
Eigen::Vector3f | max | ||
) |
std::string visionx::tools::getHardwareId | ( | ) |
Retrieve hardware id to identify local machine.
This method generates a hardware id from the mac address.
std::map<uint32_t, pcl::PointIndices> visionx::tools::getLabelMap | ( | const PointCloudT & | labeledCloud, |
bool | excludeZero = true |
||
) |
Definition at line 144 of file PCLUtilities.h.
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.
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.
visionx::PointContentType visionx::tools::getPointContentType | ( | ) |
Definition at line 41 of file PointCloudConversions.h.
visionx::PointContentType getPointContentType< pcl::PointNormal > | ( | ) |
Definition at line 46 of file PointCloudConversions.cpp.
visionx::PointContentType getPointContentType< pcl::PointXYZ > | ( | ) |
Definition at line 33 of file PointCloudConversions.cpp.
visionx::PointContentType getPointContentType< pcl::PointXYZI > | ( | ) |
Definition at line 41 of file PointCloudConversions.cpp.
visionx::PointContentType getPointContentType< pcl::PointXYZL > | ( | ) |
Definition at line 37 of file PointCloudConversions.cpp.
visionx::PointContentType getPointContentType< pcl::PointXYZRGBA > | ( | ) |
Definition at line 50 of file PointCloudConversions.cpp.
visionx::PointContentType getPointContentType< pcl::PointXYZRGBL > | ( | ) |
Definition at line 54 of file PointCloudConversions.cpp.
visionx::PointContentType getPointContentType< pcl::PointXYZRGBNormal > | ( | ) |
Definition at line 58 of file PointCloudConversions.cpp.
std::map<uint32_t, simox::AxisAlignedBoundingBox> visionx::tools::getSegmentAABBs | ( | const pcl::PointCloud< PointT > & | pointCloud, |
const std::map< uint32_t, IndicesT > & | segmentIndices | ||
) |
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.
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.
labeledCloud | A labeled point cloud. |
excludeZero | If true, points with label == 0 are ignored. |
Definition at line 74 of file segments.h.
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
.
Definition at line 85 of file segments.h.
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.
std::string imageTypeToTypeName | ( | const ImageType | imageType | ) |
Converts an image type into a string integer.
imageType | Image type |
Definition at line 70 of file TypeMapping.cpp.
bool visionx::tools::isColored | ( | PointContentType | type | ) |
Definition at line 95 of file PointCloudConversions.cpp.
bool visionx::tools::isColored | ( | visionx::PointContentType | type | ) |
Indicate whether this point type contains colors.
bool visionx::tools::isLabeled | ( | PointContentType | type | ) |
Definition at line 108 of file PointCloudConversions.cpp.
bool visionx::tools::isLabeled | ( | visionx::PointContentType | type | ) |
Indicate whether this point type contains labels.
void visionx::tools::relabel | ( | pcl::PointCloud< PointT > & | pointCloud, |
const std::map< uint32_t, pcl::PointIndices > & | segmentIndices | ||
) |
void visionx::tools::relabel | ( | pcl::PointCloud< PointT > & | pointCloud, |
const std::map< uint32_t, pcl::PointIndices::Ptr > & | segmentIndices | ||
) |
|
inline |
Definition at line 142 of file ImageUtil.h.
simox::AxisAlignedBoundingBox toAABB | ( | const BoundingBox3D & | boundingBox | ) |
BoundingBox3D toBoundingBox3D | ( | const Eigen::Vector3f & | min, |
const Eigen::Vector3f & | max | ||
) |
BoundingBox3D toBoundingBox3D | ( | const simox::AxisAlignedBoundingBox & | aabb | ) |
std::string visionx::tools::toString | ( | PointContentType | pointContent | ) |
Definition at line 765 of file PointCloudConversions.cpp.
std::string visionx::tools::toString | ( | visionx::PointContentType | pointContent | ) |
visionx::ImageType typeNameToImageType | ( | const std::string & | imageTypeName | ) |
Converts an image type name as string into an ImageType integer.
imageTypeName | Image type string |
Definition at line 42 of file TypeMapping.cpp.