Classes | Functions | Variables
surface_perception Namespace Reference

Classes

struct  Object
 Object represents a segmented object on a surface. More...
class  Segmentation
 Segmentation is the algorithm for tabletop/shelf segmentation. More...
struct  Surface
 Represents a surface. More...
class  SurfaceFinder
 SurfaceFinder attempt to find multiple horizontal surfaces given a shelf scene. More...
class  SurfaceHistoryRecorder
 SurfaceHistoryRecorder records information of time, iteration and history of each surface. More...
struct  SurfaceObjects
 Represents a surface with objects above it. More...
class  SurfaceViz
 A visualization for a surface. More...

Functions

bool FindObjectsOnSurfaces (PointCloudC::Ptr cloud, pcl::PointIndicesPtr indices, const std::vector< Surface > &surface_vec, double margin_above_surface, double cluster_distance, int min_cluster_size, int max_cluster_size, std::vector< SurfaceObjects > *surfaces_objects_vec)
bool FindObjectsOnSurfaces (pcl::PointCloud< pcl::PointXYZRGB >::Ptr cloud, pcl::PointIndicesPtr indices, const std::vector< Surface > &surface_vec, double margin_above_surface, double cluster_distance, int min_cluster_size, int max_cluster_size, std::vector< SurfaceObjects > *surfaces_objects_vec)
 The algorithm that segments the objects above each of a list of surfaces.
bool FindSurfaces (PointCloudC::Ptr cloud, pcl::PointIndices::Ptr indices, double max_point_distance, double horizontal_tolerance_degrees, int min_surface_size, int min_surface_exploration_iteration, std::vector< Surface > *surfaces)
bool FindSurfaces (pcl::PointCloud< pcl::PointXYZRGB >::Ptr cloud, pcl::PointIndicesPtr indices, double max_point_distance, double horizontal_tolerance_degrees, int min_surface_size, int min_surface_exploration_iteration, std::vector< Surface > *surfaces)
 Finds horizonal surfaces in the given point cloud.
bool FitBox (const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &input, const pcl::PointIndicesPtr &indices, const pcl::ModelCoefficients::Ptr &model, geometry_msgs::Pose *pose, geometry_msgs::Vector3 *dimensions)
 Fits an oriented bounding box around a given point cloud representing an object or a surface.
bool FitBox (const PointCloudC::Ptr &input, const pcl::PointIndices::Ptr &indices, const pcl::ModelCoefficients::Ptr &model, geometry_msgs::Pose *pose, geometry_msgs::Vector3 *dimensions)
bool FitBoxOnSurface (const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &input, const pcl::PointIndicesPtr &indices, const Surface &surface, geometry_msgs::Pose *pose, geometry_msgs::Vector3 *dimensions)
 Fits an oriented bounding box around a given point cloud representing an object resting on a surface.
visualization_msgs::MarkerArray GetAxesMarkerArray (const std::string &name_space, const std::string &frame_id, const geometry_msgs::Pose &pose, double scale)
 This helper function generates a marker array where axes are represented by three markers of colored cylinder bars.
bool GetSceneAboveSurface (pcl::PointCloud< pcl::PointXYZRGB >::Ptr cloud, pcl::PointIndices::Ptr indices, const pcl::ModelCoefficients &coefficients, double margin_above_surface, float height_limit, pcl::PointIndices::Ptr above_surface_indices)
bool GetSceneAboveSurface (pcl::PointCloud< pcl::PointXYZRGB >::Ptr cloud, pcl::PointIndicesPtr indices, const pcl::ModelCoefficients &coefficients, double margin_above_surface, float height_limit, pcl::PointIndices::Ptr above_surface_indices)
 Extracts the part of the point cloud above a given surface.
void ObjectMarkers (const std::vector< Object > &objects, std::vector< visualization_msgs::Marker > *markers)
 Generates markers for the given objects. Does not set the namespaces or IDs.
Eigen::Matrix3f StandardizeBoxOrientation (const Eigen::Matrix3f &rotation_matrix, double x_dim, double y_dim, double *updated_x_dim, double *updated_y_dim)
 Returns a standardized orientation for a box.
void SurfaceMarker (const Surface &surface, visualization_msgs::Marker *marker)
 Generates a marker for the given surface. Does not set the namespace or ID.
void SurfaceMarkers (const std::vector< SurfaceObjects > &surfaces, std::vector< visualization_msgs::Marker > *markers)
 TEST (TestStandardizeBoxOrientation, IdentityMatrix)
 TEST (TestStandardizeBoxOrientation, IdentityMatrixRotate180DegreesAroundYAxis)
 TEST (TestStandardizeBoxOrientation, IdentityMatrixRotate45DegreesAroundZAxis)
 TEST (TestStandardizeBoxOrientation, IdentityMatrixRotate135DegreesAroundZAxis)
 TEST (TestStandardizeBoxOrientation, TiltedMatrix)
 TEST (TestStandardizeBoxOrientation, TiltedMatrixRotate180DegreesAroundYAxis)
 TEST (TestStandardizeBoxOrientation, IdentityMatrixWithXLongSideYShortSdie)
 TEST (TestStandardizeBoxOrientation, TiltedMatrixWithXLongSideYShortSide)

Variables

const double kLongSide = 2.0
const double kShortSide = 1.0

Function Documentation

bool surface_perception::FindObjectsOnSurfaces ( PointCloudC::Ptr  cloud,
pcl::PointIndicesPtr  indices,
const std::vector< Surface > &  surface_vec,
double  margin_above_surface,
double  cluster_distance,
int  min_cluster_size,
int  max_cluster_size,
std::vector< SurfaceObjects > *  surfaces_objects_vec 
)

Definition at line 184 of file segmentation.cpp.

bool surface_perception::FindObjectsOnSurfaces ( pcl::PointCloud< pcl::PointXYZRGB >::Ptr  cloud,
pcl::PointIndicesPtr  indices,
const std::vector< Surface > &  surface_vec,
double  margin_above_surface,
double  cluster_distance,
int  min_cluster_size,
int  max_cluster_size,
std::vector< SurfaceObjects > *  surfaces_objects_vec 
)

The algorithm that segments the objects above each of a list of surfaces.

Parameters:
[in]cloudThe point cloud to find a surface in, where positive z points up.
[in]indicesThe indices in the point cloud to segment from.
[in]surface_vecThe vector of surfaces to segment objects from.
[in]margin_above_surfaceThe margin to extend above the surface plane, in meters.
[in]cluster_distanceThe distance between points (in meters) for those points to be considered part of separate objects.
[in]min_cluster_sizeThe minimum number of points that must be in a cluster for that cluster to be considered an object.
[in]max_cluster_sizeThe maximum number of points that can be in a cluster for that cluster to be considered an object.
[out]surfaces_objects_vecThe vector of surfaces and the objects above each surface that were found.
Returns:
true if the segmentation was successful, false otherwise.
bool surface_perception::FindSurfaces ( PointCloudC::Ptr  cloud,
pcl::PointIndices::Ptr  indices,
double  max_point_distance,
double  horizontal_tolerance_degrees,
int  min_surface_size,
int  min_surface_exploration_iteration,
std::vector< Surface > *  surfaces 
)

Definition at line 98 of file segmentation.cpp.

bool surface_perception::FindSurfaces ( pcl::PointCloud< pcl::PointXYZRGB >::Ptr  cloud,
pcl::PointIndicesPtr  indices,
double  max_point_distance,
double  horizontal_tolerance_degrees,
int  min_surface_size,
int  min_surface_exploration_iteration,
std::vector< Surface > *  surfaces 
)

Finds horizonal surfaces in the given point cloud.

Parameters:
[in]cloudThe point cloud to find a surface in, where positive z points up.
[in]indicesThe indices in the point cloud to find a surface in.
[in]max_point_distanceThe maximum distance between a plane and a point, in order to be considered as part of a surface.
[in]horizontal_tolerance_degreesThe tolerance, in degrees, for a surface to be considered horizontal.
[in]min_surface_sizeThe required number of points for a surface.
[in]min_surface_exploration_iterationThe required number of iteration for the surface exploration algorithm.
[out]surfacesThe vector of detected surfaces (may be changed even if no surface is found).
Returns:
true if a surface was found, false otherwise.
bool surface_perception::FitBox ( const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &  input,
const pcl::PointIndicesPtr &  indices,
const pcl::ModelCoefficients::Ptr &  model,
geometry_msgs::Pose pose,
geometry_msgs::Vector3 dimensions 
)

Fits an oriented bounding box around a given point cloud representing an object or a surface.

Note: this algorithm is adapted from the simple_grasping package.

Parameters:
[in]inputThe input point cloud to fit the box around.
[in]indicesThe indices in the input point cloud to use.
[in]modelThe model coefficients for the plane that the object is resting on. If fitting a box around a surface, use the surface's own coefficients.
[out]poseThe pose representing the center of the box. The z direction points "up" relative to the surface. The x and y directions are aligned with the fitted box, with the x direction pointing toward the shorter side of the box.
[out]dimensionsThe dimensions of the oriented bounding box. x, y, and z correspond to the directions of the pose.
Returns:
reports true when a bounding box can be constructed for the object, or false if the construction fails.
bool surface_perception::FitBox ( const PointCloudC::Ptr &  input,
const pcl::PointIndices::Ptr &  indices,
const pcl::ModelCoefficients::Ptr &  model,
geometry_msgs::Pose pose,
geometry_msgs::Vector3 dimensions 
) [static]

Definition at line 109 of file shape_extraction.cpp.

bool surface_perception::FitBoxOnSurface ( const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &  input,
const pcl::PointIndicesPtr &  indices,
const Surface &  surface,
geometry_msgs::Pose pose,
geometry_msgs::Vector3 dimensions 
)

Fits an oriented bounding box around a given point cloud representing an object resting on a surface.

Note: this algorithm is adapted from the simple_grasping package.

Parameters:
[in]inputThe input point cloud to fit the box around.
[in]indicesThe indices in the input point cloud to use.
[in]surfaceThe surface that the object is resting on.
[out]poseThe pose representing the center of the box. The z direction points "up" relative to the surface. The x and y directions are aligned with the fitted box, with the x direction pointing toward the shorter side of the box.
[out]dimensionsThe dimensions of the oriented bounding box. x, y, and z correspond to the directions of the pose.
Returns:
reports true when a bounding box can be constructed for the object, or false if the construction fails.

Definition at line 256 of file shape_extraction.cpp.

visualization_msgs::MarkerArray surface_perception::GetAxesMarkerArray ( const std::string &  name_space,
const std::string &  frame_id,
const geometry_msgs::Pose pose,
double  scale 
)

This helper function generates a marker array where axes are represented by three markers of colored cylinder bars.

Example usage:

   geometry_msgs::Pose pose;
   pose.position.x = pose.position.y = pose.position.z = 1.0;
   pose.orientation.x = pose.orientation.y = pose.orientation.z = 0.0;
   pose.orientation.w = 1.0;
   visualization_msgs::MarkerArray axes_markers =
       surface_perception::GetAxesMarkerArray("markers", "base_link", pose,
                       1.0);
Parameters:
[in]name_spaceThe name space for the three markers to be created.
[in]frame_idThe id of the frame where the markers will be.
[in]poseThe pose of the origin where the three axes intersect.
[in]scaleThe length of each colored cylinder bars. The cylinder diameters are 10% of scale, or 1 cm if 10% scale is less than 1 cm.
Returns:
A MarkerArray of three Marker objects is returned where x-axis is a red cylinder, y-axis is a green cylinder and z-axis is a blue cylinder.

Definition at line 12 of file axes_marker.cpp.

bool surface_perception::GetSceneAboveSurface ( pcl::PointCloud< pcl::PointXYZRGB >::Ptr  cloud,
pcl::PointIndices::Ptr  indices,
const pcl::ModelCoefficients &  coefficients,
double  margin_above_surface,
float  height_limit,
pcl::PointIndices::Ptr  above_surface_indices 
)

Definition at line 142 of file segmentation.cpp.

bool surface_perception::GetSceneAboveSurface ( pcl::PointCloud< pcl::PointXYZRGB >::Ptr  cloud,
pcl::PointIndicesPtr  indices,
const pcl::ModelCoefficients &  coefficients,
double  margin_above_surface,
float  height_limit,
pcl::PointIndices::Ptr  above_surface_indices 
)

Extracts the part of the point cloud above a given surface.

Parameters:
[in]cloudThe point cloud to find a surface in, where positive z points up.
[in]indicesThe indices in the point cloud to extract from.
[in]coefficientsThe coefficients of a plane representing a horizontal surface: ax + by + cz + d = 0, where a, b, c, and d are the first four coefficients.
[in]margin_above_surfaceThe margin to extend above the surface plane, in meters.
[in]height_limitThe maximum height of each surface scene. The height is defined as the distance from one plane to the plane above. If there's no plane above, then height_limit should be some value larger or equal to maximum point height in the input point cloud scene.
[out]above_surface_indicesThe indices in the given point cloud representing the points above the plane (and the margin above the plane).
Returns:
true if the plane model coefficients are valid and a non-zero number of points were found above the plane, false otherwise.
void surface_perception::ObjectMarkers ( const std::vector< Object > &  objects,
std::vector< visualization_msgs::Marker > *  markers 
)

Generates markers for the given objects. Does not set the namespaces or IDs.

Definition at line 54 of file visualization.cpp.

Eigen::Matrix3f surface_perception::StandardizeBoxOrientation ( const Eigen::Matrix3f &  rotation_matrix,
double  x_dim,
double  y_dim,
double *  updated_x_dim,
double *  updated_y_dim 
)

Returns a standardized orientation for a box.

The standardized box orientation is defined as the following: 1. The x dimension of the box will be smaller than the y dimension of the box. 2. The x-axis of the box will point in the positive x direction. 3. The z-axis will point in the same direction as given, and the y-axis will be set according to the right hand rule.

Parameters:
[in]rotaton_matrixThe given rotation matrix of the box on a plane. The z basis vector is assumed to be the same as the plane normal vector.
[in]x_dimensionThe current x dimension of the box.
[in]y_dimensionThe current y dimension of the box.
[out]updated_x_dimIf the x basis vector and y basis vector are swapped, updated_x_dim will point to the value of y_dim. Otherwise, it points to the value of x_dim.
[out]updated_y_dimIf the y basis vector and x basis vector are swapped, updated_y_dim will point to the value of x_dim. Otherwise, it points to the value of y_dim.
Returns:
A rotation matrix with the standardized box orientation is returned, based on the given rotation matrix and dimensions.

Definition at line 283 of file shape_extraction.cpp.

void surface_perception::SurfaceMarker ( const Surface &  surface,
visualization_msgs::Marker *  marker 
)

Generates a marker for the given surface. Does not set the namespace or ID.

Definition at line 44 of file visualization.cpp.

void surface_perception::SurfaceMarkers ( const std::vector< SurfaceObjects > &  surfaces,
std::vector< visualization_msgs::Marker > *  markers 
)

Generates markers for the given surfaces. Sets namespaces and IDs like: First surface: ns=surface, id=0 First object on first surface: ns=surface_0, id=0

Definition at line 69 of file visualization.cpp.

surface_perception::TEST ( TestStandardizeBoxOrientation  ,
IdentityMatrix   
)

Definition at line 13 of file rotation_matrix_test.cpp.

surface_perception::TEST ( TestStandardizeBoxOrientation  ,
IdentityMatrixRotate180DegreesAroundYAxis   
)

Definition at line 26 of file rotation_matrix_test.cpp.

surface_perception::TEST ( TestStandardizeBoxOrientation  ,
IdentityMatrixRotate45DegreesAroundZAxis   
)

Definition at line 48 of file rotation_matrix_test.cpp.

surface_perception::TEST ( TestStandardizeBoxOrientation  ,
IdentityMatrixRotate135DegreesAroundZAxis   
)

Definition at line 70 of file rotation_matrix_test.cpp.

surface_perception::TEST ( TestStandardizeBoxOrientation  ,
TiltedMatrix   
)

Definition at line 92 of file rotation_matrix_test.cpp.

surface_perception::TEST ( TestStandardizeBoxOrientation  ,
TiltedMatrixRotate180DegreesAroundYAxis   
)

Definition at line 114 of file rotation_matrix_test.cpp.

surface_perception::TEST ( TestStandardizeBoxOrientation  ,
IdentityMatrixWithXLongSideYShortSdie   
)

Definition at line 136 of file rotation_matrix_test.cpp.

surface_perception::TEST ( TestStandardizeBoxOrientation  ,
TiltedMatrixWithXLongSideYShortSide   
)

Definition at line 158 of file rotation_matrix_test.cpp.


Variable Documentation

const double surface_perception::kLongSide = 2.0

Definition at line 10 of file rotation_matrix_test.cpp.

const double surface_perception::kShortSide = 1.0

Definition at line 11 of file rotation_matrix_test.cpp.



surface_perception
Author(s): Yu-Tang Peng
autogenerated on Thu Jun 6 2019 17:36:21