Namespaces | |
namespace | angles |
namespace | areas |
namespace | distances |
namespace | intersections |
namespace | nearest |
namespace | norms |
namespace | projections |
namespace | statistics |
namespace | transforms |
Classes | |
struct | Leaf |
Simple leaf (3d box) structure) holding a centroid and the number of points in the leaf. More... | |
Functions | |
void | cerr_p (const std::vector< double > &p) |
void | cerr_p (const geometry_msgs::Point32 &p) |
Write the point data to screen (stderr). | |
void | cerr_poly (const geometry_msgs::Polygon &poly) |
Write the polygon data to screen (stderr). | |
bool | checkPointEqual (const geometry_msgs::Point32 &p1, const geometry_msgs::Point32 &p2, double eps=1e-10) |
Check whether two given points are equal with some epsilon delta. | |
void | cross (const std::vector< double > &p1, const std::vector< double > &p2, std::vector< double > &p3) |
Compute the cross product between two points (vectors). | |
geometry_msgs::Point32 | cross (const geometry_msgs::Point32 &p1, const std::vector< double > &p2) |
Compute the cross product between two points (vectors). | |
geometry_msgs::Point32 | cross (const std::vector< double > &p1, const geometry_msgs::Point32 &p2) |
Compute the cross product between two points (vectors). | |
geometry_msgs::Point32 | cross (const geometry_msgs::Point32 &p1, const geometry_msgs::Point32 &p2) |
Compute the cross product between two points (vectors). | |
double | dot (const std::vector< double > &p1, const std::vector< double > &p2) |
Compute the dot product between two points (vectors). | |
double | dot (const geometry_msgs::Vector3 &p1, const geometry_msgs::Vector3 &p2) |
Compute the dot product between two points (vectors). | |
double | dot (const geometry_msgs::Vector3 &p1, const geometry_msgs::Point32 &p2) |
Compute the dot product between two points (vectors). | |
double | dot (const geometry_msgs::Point32 &p1, const geometry_msgs::Vector3 &p2) |
Compute the dot product between two points (vectors). | |
double | dot (const geometry_msgs::Point &p1, const geometry_msgs::Point32 &p2) |
Compute the dot product between two points (vectors). | |
double | dot (const geometry_msgs::Point32 &p1, const geometry_msgs::Point &p2) |
Compute the dot product between two points (vectors). | |
double | dot (const geometry_msgs::Point &p1, const geometry_msgs::Point &p2) |
Compute the dot product between two points (vectors). | |
double | dot (const geometry_msgs::Point32 &p1, const geometry_msgs::Point32 &p2) |
Compute the dot product between two points (vectors). | |
void | downsamplePointCloud (const sensor_msgs::PointCloud &points, sensor_msgs::PointCloud &points_down, geometry_msgs::Point leaf_size) |
Downsample a Point Cloud using a voxelized grid approach. | |
void | downsamplePointCloud (sensor_msgs::PointCloudConstPtr points, sensor_msgs::PointCloud &points_down, geometry_msgs::Point leaf_size, std::vector< Leaf > &leaves, int d_idx, double cut_distance) |
Downsample a Point Cloud using a voxelized grid approach. | |
void | downsamplePointCloud (const sensor_msgs::PointCloud &points, sensor_msgs::PointCloud &points_down, geometry_msgs::Point leaf_size, std::vector< Leaf > &leaves, int d_idx, double cut_distance) |
Downsample a Point Cloud using a voxelized grid approach. | |
void | downsamplePointCloud (const sensor_msgs::PointCloud &points, const std::vector< int > &indices, sensor_msgs::PointCloud &points_down, geometry_msgs::Point leaf_size, std::vector< Leaf > &leaves, int d_idx, double cut_distance) |
Downsample a Point Cloud using a voxelized grid approach. | |
std::string | getAvailableChannels (const sensor_msgs::PointCloudConstPtr &cloud) |
Get the available dimensions as a space separated string. | |
std::string | getAvailableChannels (const sensor_msgs::PointCloud &cloud) |
Get the available dimensions as a space separated string. | |
int | getChannelIndex (sensor_msgs::PointCloudConstPtr points, std::string channel_name) |
Get the index of a specified dimension/channel in a point cloud. | |
int | getChannelIndex (const sensor_msgs::PointCloud &points, std::string channel_name) |
Get the index of a specified dimension/channel in a point cloud. | |
void | getCoordinateSystemOnPlane (const std::vector< double > &plane_coeff, Eigen::Vector3d &u, Eigen::Vector3d &v) |
Get a u-v-n coordinate system that lies on a plane defined by its normal. | |
void | getPointAsFloatArray (const sensor_msgs::PointCloud &points, int index, std::vector< float > &array, std::vector< int > channels) |
Create a quick copy of a point and its associated channels and return the data as a float vector. | |
void | getPointAsFloatArray (const sensor_msgs::PointCloud &points, int index, std::vector< float > &array, int start_channel, int end_channel) |
Create a quick copy of a point and its associated channels and return the data as a float vector. | |
void | getPointAsFloatArray (const sensor_msgs::PointCloud &points, int index, std::vector< float > &array, int nr_channels) |
Create a quick copy of a point and its associated channels and return the data as a float vector. | |
void | getPointAsFloatArray (const sensor_msgs::PointCloud &points, int index, std::vector< float > &array) |
Create a quick copy of a point and its associated channels and return the data as a float vector. | |
void | getPointCloud (const sensor_msgs::PointCloud &input, const std::vector< int > &indices, sensor_msgs::PointCloud &output) |
Create a new point cloud object by copying the data from a given input point cloud using a set of indices. | |
void | getPointCloudOutside (const sensor_msgs::PointCloud &input, std::vector< int > indices, sensor_msgs::PointCloud &output) |
Create a new point cloud object by copying the data from a given input point cloud using a set of indices. | |
void | getPointIndicesAxisParallelNormals (const sensor_msgs::PointCloud &points, int nx, int ny, int nz, double eps_angle, const geometry_msgs::Point32 &axis, std::vector< int > &indices) |
Get the point indices from a cloud, whose normals are close to parallel with a given axis direction. | |
void | getPointIndicesAxisPerpendicularNormals (const sensor_msgs::PointCloud &points, int nx, int ny, int nz, double eps_angle, const geometry_msgs::Point32 &axis, std::vector< int > &indices) |
Get the point indices from a cloud, whose normals are close to perpendicular to a given axis direction. | |
void | normalizePoint (geometry_msgs::Point32 &p) |
Normalize a point and return the result in place. | |
void | normalizePoint (const geometry_msgs::Point32 &p, geometry_msgs::Point32 &q) |
Normalize a point. |
void cloud_geometry::cerr_p | ( | const std::vector< double > & | p | ) | [inline] |
void cloud_geometry::cerr_p | ( | const geometry_msgs::Point32 & | p | ) | [inline] |
void cloud_geometry::cerr_poly | ( | const geometry_msgs::Polygon & | poly | ) | [inline] |
bool cloud_geometry::checkPointEqual | ( | const geometry_msgs::Point32 & | p1, | |
const geometry_msgs::Point32 & | p2, | |||
double | eps = 1e-10 | |||
) | [inline] |
void cloud_geometry::cross | ( | const std::vector< double > & | p1, | |
const std::vector< double > & | p2, | |||
std::vector< double > & | p3 | |||
) | [inline] |
geometry_msgs::Point32 cloud_geometry::cross | ( | const geometry_msgs::Point32 & | p1, | |
const std::vector< double > & | p2 | |||
) | [inline] |
geometry_msgs::Point32 cloud_geometry::cross | ( | const std::vector< double > & | p1, | |
const geometry_msgs::Point32 & | p2 | |||
) | [inline] |
geometry_msgs::Point32 cloud_geometry::cross | ( | const geometry_msgs::Point32 & | p1, | |
const geometry_msgs::Point32 & | p2 | |||
) | [inline] |
double cloud_geometry::dot | ( | const std::vector< double > & | p1, | |
const std::vector< double > & | p2 | |||
) | [inline] |
double cloud_geometry::dot | ( | const geometry_msgs::Vector3 & | p1, | |
const geometry_msgs::Vector3 & | p2 | |||
) | [inline] |
double cloud_geometry::dot | ( | const geometry_msgs::Vector3 & | p1, | |
const geometry_msgs::Point32 & | p2 | |||
) | [inline] |
double cloud_geometry::dot | ( | const geometry_msgs::Point32 & | p1, | |
const geometry_msgs::Vector3 & | p2 | |||
) | [inline] |
double cloud_geometry::dot | ( | const geometry_msgs::Point & | p1, | |
const geometry_msgs::Point32 & | p2 | |||
) | [inline] |
double cloud_geometry::dot | ( | const geometry_msgs::Point32 & | p1, | |
const geometry_msgs::Point & | p2 | |||
) | [inline] |
double cloud_geometry::dot | ( | const geometry_msgs::Point & | p1, | |
const geometry_msgs::Point & | p2 | |||
) | [inline] |
double cloud_geometry::dot | ( | const geometry_msgs::Point32 & | p1, | |
const geometry_msgs::Point32 & | p2 | |||
) | [inline] |
void cloud_geometry::downsamplePointCloud | ( | const sensor_msgs::PointCloud & | points, | |
sensor_msgs::PointCloud & | points_down, | |||
geometry_msgs::Point | leaf_size | |||
) |
Downsample a Point Cloud using a voxelized grid approach.
points | the point cloud message | |
points_down | the resultant downsampled point cloud | |
leaf_size | the voxel leaf dimensions |
void cloud_geometry::downsamplePointCloud | ( | sensor_msgs::PointCloudConstPtr | points, | |
sensor_msgs::PointCloud & | points_down, | |||
geometry_msgs::Point | leaf_size, | |||
std::vector< Leaf > & | leaves, | |||
int | d_idx, | |||
double | cut_distance | |||
) |
Downsample a Point Cloud using a voxelized grid approach.
points | the point cloud message | |
indices | a set of point indices | |
points_down | the resultant downsampled point cloud | |
leaf_size | the voxel leaf dimensions | |
leaves | a vector of already existing leaves (empty for the first call) | |
d_idx | the index of the channel providing distance data (set to -1 if nonexistant) | |
cut_distance | the maximum admissible distance of a point from the viewpoint (default: FLT_MAX) |
void cloud_geometry::downsamplePointCloud | ( | const sensor_msgs::PointCloud & | points, | |
sensor_msgs::PointCloud & | points_down, | |||
geometry_msgs::Point | leaf_size, | |||
std::vector< Leaf > & | leaves, | |||
int | d_idx, | |||
double | cut_distance | |||
) |
Downsample a Point Cloud using a voxelized grid approach.
points | the point cloud message | |
indices | a set of point indices | |
points_down | the resultant downsampled point cloud | |
leaf_size | the voxel leaf dimensions | |
leaves | a vector of already existing leaves (empty for the first call) | |
d_idx | the index of the channel providing distance data (set to -1 if nonexistant) | |
cut_distance | the maximum admissible distance of a point from the viewpoint (default: FLT_MAX) |
void cloud_geometry::downsamplePointCloud | ( | const sensor_msgs::PointCloud & | points, | |
const std::vector< int > & | indices, | |||
sensor_msgs::PointCloud & | points_down, | |||
geometry_msgs::Point | leaf_size, | |||
std::vector< Leaf > & | leaves, | |||
int | d_idx, | |||
double | cut_distance | |||
) |
Downsample a Point Cloud using a voxelized grid approach.
points | a pointer to the point cloud message | |
points_down | the resultant downsampled point cloud | |
leaf_size | the voxel leaf dimensions | |
leaves | a vector of already existing leaves (empty for the first call) | |
d_idx | the index of the channel providing distance data (set to -1 if nonexistant) | |
cut_distance | the maximum admissible distance of a point from the viewpoint (default: FLT_MAX) |
std::string cloud_geometry::getAvailableChannels | ( | const sensor_msgs::PointCloudConstPtr & | cloud | ) |
std::string cloud_geometry::getAvailableChannels | ( | const sensor_msgs::PointCloud & | cloud | ) |
int cloud_geometry::getChannelIndex | ( | sensor_msgs::PointCloudConstPtr | points, | |
std::string | channel_name | |||
) |
int cloud_geometry::getChannelIndex | ( | const sensor_msgs::PointCloud & | points, | |
std::string | channel_name | |||
) |
void cloud_geometry::getCoordinateSystemOnPlane | ( | const std::vector< double > & | plane_coeff, | |
Eigen::Vector3d & | u, | |||
Eigen::Vector3d & | v | |||
) | [inline] |
void cloud_geometry::getPointAsFloatArray | ( | const sensor_msgs::PointCloud & | points, | |
int | index, | |||
std::vector< float > & | array, | |||
std::vector< int > | channels | |||
) | [inline] |
Create a quick copy of a point and its associated channels and return the data as a float vector.
points | the point cloud data message | |
index | the index of the point to return | |
array | the vector containing the result | |
start_channel | the first channel to start copying data from | |
end_channel | the last channel to stop copying data at |
void cloud_geometry::getPointAsFloatArray | ( | const sensor_msgs::PointCloud & | points, | |
int | index, | |||
std::vector< float > & | array, | |||
int | start_channel, | |||
int | end_channel | |||
) | [inline] |
Create a quick copy of a point and its associated channels and return the data as a float vector.
points | the point cloud data message | |
index | the index of the point to return | |
array | the vector containing the result | |
start_channel | the first channel to start copying data from | |
end_channel | the last channel to stop copying data at |
void cloud_geometry::getPointAsFloatArray | ( | const sensor_msgs::PointCloud & | points, | |
int | index, | |||
std::vector< float > & | array, | |||
int | nr_channels | |||
) | [inline] |
Create a quick copy of a point and its associated channels and return the data as a float vector.
points | the point cloud data message | |
index | the index of the point to return | |
array | the vector containing the result | |
nr_channels | the number of channels to copy (starting with the first channel) |
void cloud_geometry::getPointAsFloatArray | ( | const sensor_msgs::PointCloud & | points, | |
int | index, | |||
std::vector< float > & | array | |||
) | [inline] |
void cloud_geometry::getPointCloud | ( | const sensor_msgs::PointCloud & | input, | |
const std::vector< int > & | indices, | |||
sensor_msgs::PointCloud & | output | |||
) |
void cloud_geometry::getPointCloudOutside | ( | const sensor_msgs::PointCloud & | input, | |
std::vector< int > | indices, | |||
sensor_msgs::PointCloud & | output | |||
) |
void cloud_geometry::getPointIndicesAxisParallelNormals | ( | const sensor_msgs::PointCloud & | points, | |
int | nx, | |||
int | ny, | |||
int | nz, | |||
double | eps_angle, | |||
const geometry_msgs::Point32 & | axis, | |||
std::vector< int > & | indices | |||
) |
Get the point indices from a cloud, whose normals are close to parallel with a given axis direction.
points | the point cloud message | |
nx | the normal X channel index | |
ny | the normal Y channel index | |
nz | the normal Z channel index | |
axis | the given axis direction | |
eps_angle | the maximum allowed difference threshold between the normal and the axis (in radians) | |
indices | the resultant indices |
void cloud_geometry::getPointIndicesAxisPerpendicularNormals | ( | const sensor_msgs::PointCloud & | points, | |
int | nx, | |||
int | ny, | |||
int | nz, | |||
double | eps_angle, | |||
const geometry_msgs::Point32 & | axis, | |||
std::vector< int > & | indices | |||
) |
Get the point indices from a cloud, whose normals are close to perpendicular to a given axis direction.
points | the point cloud message | |
nx | the normal X channel index | |
ny | the normal Y channel index | |
nz | the normal Z channel index | |
axis | the given axis direction | |
eps_angle | the maximum allowed difference threshold between the normal and the axis (in radians) | |
indices | the resultant indices |
void cloud_geometry::normalizePoint | ( | geometry_msgs::Point32 & | p | ) | [inline] |