Classes | Functions
simple_grasping Namespace Reference

Classes

class  BasicGraspingPerception
 ROS wrapper for shape grasp planner + object support segmentation. More...
class  ObjectSupportSegmentation
 Class that segments a point cloud into objects and supporting surfaces. More...
class  ShapeGraspPlanner
 A simple grasp planner that uses the bounding box shape to generate viable grasps. More...

Functions

void colorizeCloud (pcl::PointCloud< pcl::PointXYZRGB > &cloud, float hue)
 Update rgb component of an XYZRGB cloud to a new HSV color.
template<typename PointT >
double distancePointToPlane (const PointT &point, const pcl::ModelCoefficients::Ptr plane)
 Get distance from point to plane.
double distancePointToPlane (const Eigen::Vector4f &point, const pcl::ModelCoefficients::Ptr plane)
 Get distance from point to plane.
bool extractShape (const pcl::PointCloud< pcl::PointXYZRGB > &input, pcl::PointCloud< pcl::PointXYZRGB > &output, shape_msgs::SolidPrimitive &shape, geometry_msgs::Pose &pose)
 Find the smallest shape primitive we can fit around this object.
bool extractShape (const pcl::PointCloud< pcl::PointXYZRGB > &input, const pcl::ModelCoefficients::Ptr model, pcl::PointCloud< pcl::PointXYZRGB > &output, shape_msgs::SolidPrimitive &shape, geometry_msgs::Pose &pose)
 Find the smallest shape primitive we can fit around this object, given the plane parameters.
bool extractUnorientedBoundingBox (const pcl::PointCloud< pcl::PointXYZRGB > &input, shape_msgs::SolidPrimitive &shape, geometry_msgs::Pose &pose)
 Find a bounding box around a cloud. This method does not attempt to find best orientation and so the bounding box will be oriented with the frame of the cloud.
void hsv2rgb (const float h, const float s, const float v, float &r, float &g, float &b)
 Fill in RGB values from HSV values.
moveit_msgs::GripperTranslation makeGripperTranslation (std::string frame, double min, double desired, double x_axis=1.0, double y_axis=0.0, double z_axis=0.0)
Eigen::Quaterniond quaternionFromEuler (float yaw, float pitch, float roll)

Function Documentation

void simple_grasping::colorizeCloud ( pcl::PointCloud< pcl::PointXYZRGB > &  cloud,
float  hue 
)

Update rgb component of an XYZRGB cloud to a new HSV color.

Parameters:
cloudThe cloud to update.
hueThe hue to apply.

Definition at line 67 of file cloud_tools.cpp.

template<typename PointT >
double simple_grasping::distancePointToPlane ( const PointT &  point,
const pcl::ModelCoefficients::Ptr  plane 
)

Get distance from point to plane.

Parameters:
pointThe point.
planePlane coefficients.

Definition at line 71 of file cloud_tools.h.

double simple_grasping::distancePointToPlane ( const Eigen::Vector4f &  point,
const pcl::ModelCoefficients::Ptr  plane 
)

Get distance from point to plane.

Parameters:
pointThe point.
planePlane coefficients.

Definition at line 93 of file cloud_tools.cpp.

bool simple_grasping::extractShape ( const pcl::PointCloud< pcl::PointXYZRGB > &  input,
pcl::PointCloud< pcl::PointXYZRGB > &  output,
shape_msgs::SolidPrimitive &  shape,
geometry_msgs::Pose pose 
)

Find the smallest shape primitive we can fit around this object.

Parameters:
inputPoint Cloud of the object.
outputPoint Cloud transformed to the pose frame of the shape primitive fit.
shapeReturned smallest shape primitive fit.
poseThe pose of the shape primitive fit.
Returns:
True if a shape was extracted, false if we have a failure.

Definition at line 232 of file shape_extraction.cpp.

bool simple_grasping::extractShape ( const pcl::PointCloud< pcl::PointXYZRGB > &  input,
const pcl::ModelCoefficients::Ptr  model,
pcl::PointCloud< pcl::PointXYZRGB > &  output,
shape_msgs::SolidPrimitive &  shape,
geometry_msgs::Pose pose 
)

Find the smallest shape primitive we can fit around this object, given the plane parameters.

Parameters:
inputPoint Cloud of the object.
modelModel coefficients for the plane.
outputPoint Cloud transformed to the pose frame of the shape primitive fit.
shapeReturned smallest shape primitive fit.
poseThe pose of the shape primitive fit.
Returns:
True if a shape was extracted, false if we have a failure.

Definition at line 41 of file shape_extraction.cpp.

bool simple_grasping::extractUnorientedBoundingBox ( const pcl::PointCloud< pcl::PointXYZRGB > &  input,
shape_msgs::SolidPrimitive &  shape,
geometry_msgs::Pose pose 
)

Find a bounding box around a cloud. This method does not attempt to find best orientation and so the bounding box will be oriented with the frame of the cloud.

Parameters:
inputPoint Cloud of the object.
shapeThe box fit to this cloud.
poseThe pose of the shape primitive extracted.

Definition at line 253 of file shape_extraction.cpp.

void simple_grasping::hsv2rgb ( const float  h,
const float  s,
const float  v,
float &  r,
float &  g,
float &  b 
)

Fill in RGB values from HSV values.

Parameters:
hHSV hue input.
sHSV saturation input.
vHSV value input.
rRGB red output.
gRGB green output.
bRGB blue output.

Definition at line 41 of file cloud_tools.cpp.

moveit_msgs::GripperTranslation simple_grasping::makeGripperTranslation ( std::string  frame,
double  min,
double  desired,
double  x_axis = 1.0,
double  y_axis = 0.0,
double  z_axis = 0.0 
)

Definition at line 42 of file shape_grasp_planner.cpp.

Eigen::Quaterniond simple_grasping::quaternionFromEuler ( float  yaw,
float  pitch,
float  roll 
)

Definition at line 60 of file shape_grasp_planner.cpp.



simple_grasping
Author(s): Michael Ferguson
autogenerated on Thu Jun 6 2019 19:12:06