cloud_geometry Namespace Reference

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.

Detailed Description

Author:
Radu Bogdan Rusu

Function Documentation

void cloud_geometry::cerr_p ( const std::vector< double > &  p  )  [inline]

Definition at line 405 of file point.h.

void cloud_geometry::cerr_p ( const geometry_msgs::Point32 &  p  )  [inline]

Write the point data to screen (stderr).

Parameters:
p the point

Definition at line 400 of file point.h.

void cloud_geometry::cerr_poly ( const geometry_msgs::Polygon &  poly  )  [inline]

Write the polygon data to screen (stderr).

Parameters:
poly the polygon

Definition at line 417 of file point.h.

bool cloud_geometry::checkPointEqual ( const geometry_msgs::Point32 &  p1,
const geometry_msgs::Point32 &  p2,
double  eps = 1e-10 
) [inline]

Check whether two given points are equal with some epsilon delta.

Parameters:
p1 a pointer to the first point
p2 a pointer to the second point
eps the maximum allowed difference between the points' values

Definition at line 59 of file point.h.

void cloud_geometry::cross ( const std::vector< double > &  p1,
const std::vector< double > &  p2,
std::vector< double > &  p3 
) [inline]

Compute the cross product between two points (vectors).

Parameters:
p1 the first point/vector
p2 the second point/vector
the resultant third vector p3 = p1 x p2

Definition at line 210 of file point.h.

geometry_msgs::Point32 cloud_geometry::cross ( const geometry_msgs::Point32 &  p1,
const std::vector< double > &  p2 
) [inline]

Compute the cross product between two points (vectors).

Parameters:
p1 the first point/vector
p2 the second point/vector

Definition at line 194 of file point.h.

geometry_msgs::Point32 cloud_geometry::cross ( const std::vector< double > &  p1,
const geometry_msgs::Point32 &  p2 
) [inline]

Compute the cross product between two points (vectors).

Parameters:
p1 the first point/vector
p2 the second point/vector

Definition at line 179 of file point.h.

geometry_msgs::Point32 cloud_geometry::cross ( const geometry_msgs::Point32 &  p1,
const geometry_msgs::Point32 &  p2 
) [inline]

Compute the cross product between two points (vectors).

Parameters:
p1 the first point/vector
p2 the second point/vector

Definition at line 164 of file point.h.

double cloud_geometry::dot ( const std::vector< double > &  p1,
const std::vector< double > &  p2 
) [inline]

Compute the dot product between two points (vectors).

Parameters:
p1 the first point/vector
p2 the second point/vector

Definition at line 302 of file point.h.

double cloud_geometry::dot ( const geometry_msgs::Vector3 &  p1,
const geometry_msgs::Vector3 &  p2 
) [inline]

Compute the dot product between two points (vectors).

Parameters:
p1 the first point/vector
p2 the second point/vector

Definition at line 291 of file point.h.

double cloud_geometry::dot ( const geometry_msgs::Vector3 &  p1,
const geometry_msgs::Point32 &  p2 
) [inline]

Compute the dot product between two points (vectors).

Parameters:
p1 the first point/vector
p2 the second point/vector

Definition at line 280 of file point.h.

double cloud_geometry::dot ( const geometry_msgs::Point32 &  p1,
const geometry_msgs::Vector3 &  p2 
) [inline]

Compute the dot product between two points (vectors).

Parameters:
p1 the first point/vector
p2 the second point/vector

Definition at line 269 of file point.h.

double cloud_geometry::dot ( const geometry_msgs::Point &  p1,
const geometry_msgs::Point32 &  p2 
) [inline]

Compute the dot product between two points (vectors).

Parameters:
p1 the first point/vector
p2 the second point/vector

Definition at line 258 of file point.h.

double cloud_geometry::dot ( const geometry_msgs::Point32 &  p1,
const geometry_msgs::Point &  p2 
) [inline]

Compute the dot product between two points (vectors).

Parameters:
p1 the first point/vector
p2 the second point/vector

Definition at line 247 of file point.h.

double cloud_geometry::dot ( const geometry_msgs::Point &  p1,
const geometry_msgs::Point &  p2 
) [inline]

Compute the dot product between two points (vectors).

Parameters:
p1 the first point/vector
p2 the second point/vector

Definition at line 236 of file point.h.

double cloud_geometry::dot ( const geometry_msgs::Point32 &  p1,
const geometry_msgs::Point32 &  p2 
) [inline]

Compute the dot product between two points (vectors).

Parameters:
p1 the first point/vector
p2 the second point/vector

Definition at line 225 of file point.h.

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.

Note:
this method should not be used in fast loops as it always reallocs the std::vector<Leaf> internally (!)
Parameters:
points the point cloud message
points_down the resultant downsampled point cloud
leaf_size the voxel leaf dimensions

Definition at line 453 of file point.cpp.

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.

Parameters:
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)

Definition at line 364 of file point.cpp.

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.

Parameters:
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)

Definition at line 272 of file point.cpp.

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.

Parameters:
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)

Definition at line 177 of file point.cpp.

std::string cloud_geometry::getAvailableChannels ( const sensor_msgs::PointCloudConstPtr &  cloud  ) 

Get the available dimensions as a space separated string.

Parameters:
cloud a pointer to the point cloud data message

Definition at line 95 of file point.cpp.

std::string cloud_geometry::getAvailableChannels ( const sensor_msgs::PointCloud &  cloud  ) 

Get the available dimensions as a space separated string.

Parameters:
cloud the point cloud data message

Definition at line 74 of file point.cpp.

int cloud_geometry::getChannelIndex ( sensor_msgs::PointCloudConstPtr  points,
std::string  channel_name 
)

Get the index of a specified dimension/channel in a point cloud.

Parameters:
points the point cloud
channel_name the string defining the channel name

Definition at line 61 of file point.cpp.

int cloud_geometry::getChannelIndex ( const sensor_msgs::PointCloud &  points,
std::string  channel_name 
)

Get the index of a specified dimension/channel in a point cloud.

Parameters:
points the point cloud
channel_name the string defining the channel name

Definition at line 47 of file point.cpp.

void cloud_geometry::getCoordinateSystemOnPlane ( const std::vector< double > &  plane_coeff,
Eigen::Vector3d &  u,
Eigen::Vector3d &  v 
) [inline]

Get a u-v-n coordinate system that lies on a plane defined by its normal.

Parameters:
plane_coeff the plane coefficients (containing n, the plane normal)
u the resultant u direction
v the resultant v direction

Definition at line 355 of file point.h.

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.

Parameters:
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

Definition at line 143 of file point.h.

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.

Parameters:
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

Definition at line 121 of file point.h.

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.

Parameters:
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)

Definition at line 99 of file point.h.

void cloud_geometry::getPointAsFloatArray ( const sensor_msgs::PointCloud &  points,
int  index,
std::vector< float > &  array 
) [inline]

Create a quick copy of a point and its associated channels and return the data as a float vector.

Parameters:
points the point cloud data message
index the index of the point to return
array the vector containing the result

Definition at line 78 of file point.h.

void cloud_geometry::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.

Parameters:
points the input point cloud message
indices a set of point indices
points the resultant/output point cloud message

Definition at line 466 of file point.cpp.

void cloud_geometry::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.

Parameters:
points the input point cloud message
indices a set of point indices
points the resultant/output point cloud message

Definition at line 496 of file point.cpp.

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.

Parameters:
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

Definition at line 122 of file point.cpp.

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.

Parameters:
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

Definition at line 150 of file point.cpp.

void cloud_geometry::normalizePoint ( geometry_msgs::Point32 &  p  )  [inline]

Normalize a point and return the result in place.

Parameters:
p the point/vector to normalize

Definition at line 327 of file point.h.

void cloud_geometry::normalizePoint ( const geometry_msgs::Point32 &  p,
geometry_msgs::Point32 &  q 
) [inline]

Normalize a point.

Parameters:
p the point/vector to normalize
q the resulted normalized point/vector

Definition at line 313 of file point.h.

 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Defines


stereo_wall_detection
Author(s): Radu Bogdan Rusu
autogenerated on Fri Jan 11 09:37:23 2013