| 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.  More... | |
| template<typename PointT > | |
| double | distancePointToPlane (const PointT &point, const pcl::ModelCoefficients::Ptr plane) | 
| Get distance from point to plane.  More... | |
| double | distancePointToPlane (const Eigen::Vector4f &point, const pcl::ModelCoefficients::Ptr plane) | 
| Get distance from point to plane.  More... | |
| 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.  More... | |
| 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.  More... | |
| 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.  More... | |
| void | hsv2rgb (const float h, const float s, const float v, float &r, float &g, float &b) | 
| Fill in RGB values from HSV values.  More... | |
| 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) | 
| void simple_grasping::colorizeCloud | ( | pcl::PointCloud< pcl::PointXYZRGB > & | cloud, | 
| float | hue | ||
| ) | 
Update rgb component of an XYZRGB cloud to a new HSV color.
| cloud | The cloud to update. | 
| hue | The hue to apply. | 
Definition at line 67 of file cloud_tools.cpp.
| double simple_grasping::distancePointToPlane | ( | const PointT & | point, | 
| const pcl::ModelCoefficients::Ptr | plane | ||
| ) | 
Get distance from point to plane.
| point | The point. | 
| plane | Plane 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.
| point | The point. | 
| plane | Plane 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.
| input | Point Cloud of the object. | 
| output | Point Cloud transformed to the pose frame of the shape primitive fit. | 
| shape | Returned smallest shape primitive fit. | 
| pose | The pose of the shape primitive fit. | 
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.
| input | Point Cloud of the object. | 
| model | Model coefficients for the plane. | 
| output | Point Cloud transformed to the pose frame of the shape primitive fit. | 
| shape | Returned smallest shape primitive fit. | 
| pose | The pose of the shape primitive fit. | 
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.
| input | Point Cloud of the object. | 
| shape | The box fit to this cloud. | 
| pose | The 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.
| h | HSV hue input. | 
| s | HSV saturation input. | 
| v | HSV value input. | 
| r | RGB red output. | 
| g | RGB green output. | 
| b | RGB 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.