Public Member Functions | Protected Attributes
FindContainerNode Class Reference

List of all members.

Public Member Functions

int boxFilter (const pcl::PointCloud< PointT >::Ptr &cloud, const pcl::PointCloud< PointT >::Ptr &cloud_filtered, const geometry_msgs::Vector3 &dims, const geometry_msgs::Pose &pose)
void drawBox (const geometry_msgs::Vector3 &box_dims, const geometry_msgs::PoseStamped &box_pose, const std::string &ns="box")
void executeCB (const object_manipulation_msgs::FindContainerGoalConstPtr &goal)
void findBoundingBox (const pcl::PointCloud< PointT >::Ptr &cloud, geometry_msgs::Vector3 &box_dims, geometry_msgs::PoseStamped &box_pose)
void findClusters (const pcl::PointCloud< PointT >::Ptr &cloud, std::vector< pcl::PointCloud< PointT >::Ptr > &clusters)
 FindContainerNode (std::string name)
visualization_msgs::Marker makeMarkerFromCloud (const pcl::PointCloud< PointT >::Ptr &cloud_ptr, const std::string &ns, int id=0, float scale=0.03)
void removeOutliers (const pcl::PointCloud< PointT >::Ptr &cloud_in, const pcl::PointCloud< PointT >::Ptr &cloud_out)
void splitCloudRegions (const pcl::PointCloud< PointT >::Ptr &cloud_in, const pcl::PointCloud< PointT >::Ptr &horizontal_cloud, const pcl::PointCloud< PointT >::Ptr &vertical_cloud)
 ~FindContainerNode (void)

Protected Attributes

std::string action_name_
actionlib::SimpleActionServer
< object_manipulation_msgs::FindContainerAction
as_
ros::NodeHandle nh_
geometry_msgs::Vector3 opening_dir_
ros::NodeHandle pnh_
ros::Publisher pub_cloud_
ros::Publisher pub_clusters_
ros::Publisher pub_container_
ros::Publisher pub_contents_
ros::Publisher pub_marker_
tf::TransformListener tfl_

Detailed Description

The FindContainerNode provides an action for splitting point clouds into vertical and horizontal surfaces (the 'walls' and 'contents' of a container).

Definition at line 70 of file find_container_action.cpp.


Constructor & Destructor Documentation

FindContainerNode::FindContainerNode ( std::string  name) [inline, explicit]

Definition at line 85 of file find_container_action.cpp.

Definition at line 105 of file find_container_action.cpp.


Member Function Documentation

int FindContainerNode::boxFilter ( const pcl::PointCloud< PointT >::Ptr &  cloud,
const pcl::PointCloud< PointT >::Ptr &  cloud_filtered,
const geometry_msgs::Vector3 &  dims,
const geometry_msgs::Pose pose 
) [inline]

Filter out points in a PointCloud that are not within axis-aligned dims around a pose

Definition at line 278 of file find_container_action.cpp.

void FindContainerNode::drawBox ( const geometry_msgs::Vector3 &  box_dims,
const geometry_msgs::PoseStamped &  box_pose,
const std::string &  ns = "box" 
) [inline]

Draw an rviz box

Definition at line 302 of file find_container_action.cpp.

Callback function for the FindContainerAction

Definition at line 325 of file find_container_action.cpp.

void FindContainerNode::findBoundingBox ( const pcl::PointCloud< PointT >::Ptr &  cloud,
geometry_msgs::Vector3 &  box_dims,
geometry_msgs::PoseStamped &  box_pose 
) [inline]

Find the axis-aligned bounding box of a PointCloud

Definition at line 256 of file find_container_action.cpp.

void FindContainerNode::findClusters ( const pcl::PointCloud< PointT >::Ptr &  cloud,
std::vector< pcl::PointCloud< PointT >::Ptr > &  clusters 
) [inline]

Use Euclidean clustering to find clusters in a point cloud

Definition at line 176 of file find_container_action.cpp.

visualization_msgs::Marker FindContainerNode::makeMarkerFromCloud ( const pcl::PointCloud< PointT >::Ptr &  cloud_ptr,
const std::string &  ns,
int  id = 0,
float  scale = 0.03 
) [inline]

Make an rviz Marker out of a pcl PointCloud

Definition at line 209 of file find_container_action.cpp.

void FindContainerNode::removeOutliers ( const pcl::PointCloud< PointT >::Ptr &  cloud_in,
const pcl::PointCloud< PointT >::Ptr &  cloud_out 
) [inline]

Create a filtering object and use it to remove outliers

Definition at line 163 of file find_container_action.cpp.

void FindContainerNode::splitCloudRegions ( const pcl::PointCloud< PointT >::Ptr &  cloud_in,
const pcl::PointCloud< PointT >::Ptr &  horizontal_cloud,
const pcl::PointCloud< PointT >::Ptr &  vertical_cloud 
) [inline]

Split a PointCloud into parts that are closer to horizontal and parts that are closer to vertical

Definition at line 113 of file find_container_action.cpp.


Member Data Documentation

std::string FindContainerNode::action_name_ [protected]

Definition at line 76 of file find_container_action.cpp.

Definition at line 75 of file find_container_action.cpp.

Definition at line 73 of file find_container_action.cpp.

geometry_msgs::Vector3 FindContainerNode::opening_dir_ [protected]

Definition at line 82 of file find_container_action.cpp.

Definition at line 74 of file find_container_action.cpp.

Definition at line 78 of file find_container_action.cpp.

Definition at line 79 of file find_container_action.cpp.

Definition at line 78 of file find_container_action.cpp.

Definition at line 78 of file find_container_action.cpp.

Definition at line 79 of file find_container_action.cpp.

Definition at line 77 of file find_container_action.cpp.


The documentation for this class was generated from the following file:


segmented_clutter_grasp_planner
Author(s): Kaijen Hsiao
autogenerated on Mon Oct 6 2014 12:51:51