|
| 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...
|
| |
Definition at line 32 of file Utils.h.