Static Public Member Functions | Private Types | Private Member Functions | List of all members
Utils Class Reference

#include <Utils.h>

Static Public Member Functions

static bool areSameVectors (const Eigen::VectorXd v1, const Eigen::VectorXd v2, double threshold)
 Check if given vectors are equal with a given tolerance (threshold). More...
 
static void cloudToROSMsg (PointCloudRGB::Ptr cloud, sensor_msgs::PointCloud2 &cloud_msg, const std::string &frameid="world")
 Convert XYZRGB cloud to PointCloud2. More...
 
static void cloudToROSMsg (const pcl::PCLPointCloud2 &cloud, sensor_msgs::PointCloud2 &cloud_msg, const std::string &frameid="world")
 Convert XYZRGB cloud to PointCloud2. More...
 
static void cloudToXYZRGB (PointCloudXYZ::Ptr cloud, PointCloudRGB::Ptr cloud_rgb, int R, int G, int B)
 Convert XYZ cloud to XYZRGB cloud with specified RGB values. More...
 
static void colorizeCloud (PointCloudRGB::Ptr cloud_rgb, int R, int G, int B)
 Apply RGB values to cloud. More...
 
static double computeCloudResolution (PointCloudXYZ::Ptr cloud)
 Obtain the resolution of the cloud. More...
 
static double computeCloudResolution (PointCloudRGB::Ptr cloud)
 Obtain the resolution of the cloud. More...
 
static void extractColFromMatrix (Eigen::MatrixXd &matrix, int col)
 Supress col from matrix. More...
 
static void extractRowFromMatrix (Eigen::MatrixXd &matrix, int row)
 Supress row from matrix. More...
 
static int findOnMatrix (const Eigen::VectorXd v, const Eigen::MatrixXd m, double threshold)
 Find vector as row on matrix with given threshold. Returns index of matrix row. If not found returns -1. More...
 
static int findOnVector (double value, const Eigen::VectorXd v, double threshold)
 Find value on vector with given threshold. Returns index vector of value found. If not found returns -1. More...
 
static bool getNormals (PointCloudRGB::Ptr &cloud, double normal_radius, PointCloudNormal::Ptr &normals)
 Get the normals for input cloud with specified normal's radius. More...
 
static void getVectorFromNormal (PointCloudNormal::Ptr normal, double idx, Eigen::Vector3f &vector)
 Obtain normal values as a vector. More...
 
static bool isValidCloud (PointCloudXYZ::Ptr cloud)
 Check whether cloud contains data and is not empty. More...
 
static bool isValidCloud (PointCloudRGB::Ptr cloud)
 Check whether cloud contains data and is not empty. More...
 
static bool isValidCloud (PointCloudNormal::Ptr normals)
 Check whether cloud normals contains data and is not empty. More...
 
static bool isValidCloudMsg (const sensor_msgs::PointCloud2 &cloud_msg)
 Check whether PointCloud2 contains data and is not empty. More...
 
static bool isValidMesh (pcl::PolygonMesh::Ptr mesh)
 Check whether mesh contains data and is not empty. More...
 
static bool isValidTransform (Eigen::Matrix4f transform)
 Check whether transform contains valid data and is not NaN. More...
 
static void onePointCloud (PointCloudRGB::Ptr cloud, int size, PointCloudRGB::Ptr one_point_cloud)
 Apply extract indices filter to input cloud with given indices. More...
 
static void printMatrix (const Eigen::Ref< const Eigen::MatrixXf > &matrix, const int size)
 Print on console matrix values with matrix format. More...
 
static void printTransform (const Eigen::Matrix4f &transform)
 Print on console transform values with matrix format. More...
 
static void rotateCloud (PointCloudRGB::Ptr cloud_in, PointCloudRGB::Ptr cloud_out, double roll, double pitch, double yaw)
 Apply rotation to cloud. Values given in [rad]. More...
 
static bool searchForSameRows (Eigen::MatrixXd source_m, Eigen::MatrixXd target_m, std::vector< int > &source_indx, std::vector< int > &target_indx)
 Check if both matrix have a coinciden row. More...
 
static void setPCpath (const std::string &pointcloud_folder_path)
 Set the pointcloud folder path object. More...
 
static void translateCloud (PointCloudRGB::Ptr cloud_in, PointCloudRGB::Ptr cloud_out, double x_offset=0, double y_offset=0, double z_offset=0)
 Apply translation to Cloud. Values given in [m]. More...
 

Private Types

typedef pcl::PointCloud< pcl::Normal > PointCloudNormal
 
typedef pcl::PointCloud< pcl::PointXYZRGB > PointCloudRGB
 
typedef pcl::PointCloud< pcl::PointXYZ > PointCloudXYZ
 

Private Member Functions

 Utils ()
 This class is not meant to be instantiated. More...
 
 ~Utils ()
 This class is not meant to be instantiated. More...
 

Detailed Description

Definition at line 32 of file Utils.h.

Member Typedef Documentation

typedef pcl::PointCloud<pcl::Normal> Utils::PointCloudNormal
private

Definition at line 36 of file Utils.h.

typedef pcl::PointCloud<pcl::PointXYZRGB> Utils::PointCloudRGB
private

Definition at line 35 of file Utils.h.

typedef pcl::PointCloud<pcl::PointXYZ> Utils::PointCloudXYZ
private

Definition at line 34 of file Utils.h.

Constructor & Destructor Documentation

Utils::Utils ( )
inlineprivate

This class is not meant to be instantiated.

Definition at line 43 of file Utils.h.

Utils::~Utils ( )
inlineprivate

This class is not meant to be instantiated.

Definition at line 49 of file Utils.h.

Member Function Documentation

bool Utils::areSameVectors ( const Eigen::VectorXd  v1,
const Eigen::VectorXd  v2,
double  threshold 
)
static

Check if given vectors are equal with a given tolerance (threshold).

Parameters
v1
v2
threshold
Returns
true
false

Definition at line 273 of file Utils.cpp.

void Utils::cloudToROSMsg ( PointCloudRGB::Ptr  cloud,
sensor_msgs::PointCloud2 &  cloud_msg,
const std::string &  frameid = "world" 
)
static

Convert XYZRGB cloud to PointCloud2.

Parameters
[in]cloud
[out]cloud_msg

Definition at line 100 of file Utils.cpp.

void Utils::cloudToROSMsg ( const pcl::PCLPointCloud2 &  cloud,
sensor_msgs::PointCloud2 &  cloud_msg,
const std::string &  frameid = "world" 
)
static

Convert XYZRGB cloud to PointCloud2.

Parameters
[in]cloud
[out]cloud_msg

Definition at line 107 of file Utils.cpp.

void Utils::cloudToXYZRGB ( PointCloudXYZ::Ptr  cloud,
PointCloudRGB::Ptr  cloud_rgb,
int  R,
int  G,
int  B 
)
static

Convert XYZ cloud to XYZRGB cloud with specified RGB values.

Parameters
[in]cloud
R0~255
G0~255
B0~255
[out]cloud_rgb

Definition at line 94 of file Utils.cpp.

void Utils::colorizeCloud ( PointCloudRGB::Ptr  cloud_rgb,
int  R,
int  G,
int  B 
)
static

Apply RGB values to cloud.

Parameters

Definition at line 84 of file Utils.cpp.

double Utils::computeCloudResolution ( PointCloudXYZ::Ptr  cloud)
static

Obtain the resolution of the cloud.

Parameters
cloud
Returns
double

Definition at line 114 of file Utils.cpp.

double Utils::computeCloudResolution ( PointCloudRGB::Ptr  cloud)
static

Obtain the resolution of the cloud.

Parameters
cloud
Returns
double

Definition at line 145 of file Utils.cpp.

void Utils::extractColFromMatrix ( Eigen::MatrixXd &  matrix,
int  col 
)
static

Supress col from matrix.

Parameters
matrix
col

Definition at line 304 of file Utils.cpp.

void Utils::extractRowFromMatrix ( Eigen::MatrixXd &  matrix,
int  row 
)
static

Supress row from matrix.

Parameters
matrix
row

Definition at line 315 of file Utils.cpp.

int Utils::findOnMatrix ( const Eigen::VectorXd  v,
const Eigen::MatrixXd  m,
double  threshold 
)
static

Find vector as row on matrix with given threshold. Returns index of matrix row. If not found returns -1.

Parameters
v
m
threshold
Returns
int

Definition at line 294 of file Utils.cpp.

int Utils::findOnVector ( double  value,
const Eigen::VectorXd  v,
double  threshold 
)
static

Find value on vector with given threshold. Returns index vector of value found. If not found returns -1.

Parameters
value
v
threshold
Returns
int

Definition at line 284 of file Utils.cpp.

bool Utils::getNormals ( PointCloudRGB::Ptr &  cloud,
double  normal_radius,
PointCloudNormal::Ptr &  normals 
)
static

Get the normals for input cloud with specified normal's radius.

Parameters
[in]cloud
[in]normal_radius
[out]normals
Returns
true
false

Definition at line 27 of file Utils.cpp.

void Utils::getVectorFromNormal ( PointCloudNormal::Ptr  normal,
double  idx,
Eigen::Vector3f &  vector 
)
static

Obtain normal values as a vector.

Parameters
normal
idx
vector

Definition at line 234 of file Utils.cpp.

bool Utils::isValidCloud ( PointCloudXYZ::Ptr  cloud)
static

Check whether cloud contains data and is not empty.

Parameters
cloud
Returns
true
false

Definition at line 46 of file Utils.cpp.

bool Utils::isValidCloud ( PointCloudRGB::Ptr  cloud)
static

Check whether cloud contains data and is not empty.

Parameters
cloud
Returns
true
false

Definition at line 51 of file Utils.cpp.

bool Utils::isValidCloud ( PointCloudNormal::Ptr  normals)
static

Check whether cloud normals contains data and is not empty.

Parameters
normals
Returns
true
false

Definition at line 56 of file Utils.cpp.

bool Utils::isValidCloudMsg ( const sensor_msgs::PointCloud2 &  cloud_msg)
static

Check whether PointCloud2 contains data and is not empty.

Parameters
cloud_msg
Returns
true
false

Definition at line 66 of file Utils.cpp.

bool Utils::isValidMesh ( pcl::PolygonMesh::Ptr  mesh)
static

Check whether mesh contains data and is not empty.

Parameters
mesh
Returns
true
false

Definition at line 61 of file Utils.cpp.

bool Utils::isValidTransform ( Eigen::Matrix4f  transform)
static

Check whether transform contains valid data and is not NaN.

Parameters
transform
Returns
true
false

Definition at line 71 of file Utils.cpp.

void Utils::onePointCloud ( PointCloudRGB::Ptr  cloud,
int  size,
PointCloudRGB::Ptr  one_point_cloud 
)
static

Apply extract indices filter to input cloud with given indices.

Parameters
[in]cloud_in
[in]indices
[out]cloud_out

Definition at line 188 of file Utils.cpp.

void Utils::printMatrix ( const Eigen::Ref< const Eigen::MatrixXf > &  matrix,
const int  size 
)
static

Print on console matrix values with matrix format.

Parameters
matrix
size

Definition at line 182 of file Utils.cpp.

void Utils::printTransform ( const Eigen::Matrix4f &  transform)
static

Print on console transform values with matrix format.

Parameters
transform

Definition at line 176 of file Utils.cpp.

void Utils::rotateCloud ( PointCloudRGB::Ptr  cloud_in,
PointCloudRGB::Ptr  cloud_out,
double  roll,
double  pitch,
double  yaw 
)
static

Apply rotation to cloud. Values given in [rad].

Parameters
cloud_in
cloud_out
roll
pitch
yaw

Definition at line 215 of file Utils.cpp.

bool Utils::searchForSameRows ( Eigen::MatrixXd  source_m,
Eigen::MatrixXd  target_m,
std::vector< int > &  source_indx,
std::vector< int > &  target_indx 
)
static

Check if both matrix have a coinciden row.

Parameters
source_m
target_m
source_indx
target_indx
Returns
true
false

Definition at line 245 of file Utils.cpp.

static void Utils::setPCpath ( const std::string &  pointcloud_folder_path)
static

Set the pointcloud folder path object.

Parameters
pointcloud_folder_path
void Utils::translateCloud ( PointCloudRGB::Ptr  cloud_in,
PointCloudRGB::Ptr  cloud_out,
double  x_offset = 0,
double  y_offset = 0,
double  z_offset = 0 
)
static

Apply translation to Cloud. Values given in [m].

Parameters
cloud_in
cloud_out
x_offset
y_offset
z_offset

Definition at line 203 of file Utils.cpp.


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


leica_point_cloud_processing
Author(s): Ines Lara Sicilia
autogenerated on Fri Feb 5 2021 03:20:30