Public Member Functions | Public Attributes | Protected Attributes
HandleDetectorNANNode Class Reference

List of all members.

Public Member Functions

bool cloud_cb (handle_detection2D::getHandlesNAN::Request &req, handle_detection2D::getHandlesNAN::Response &res)
void createNaNPointCloud (cv::Mat &nan_image, pcl::PointCloud< pcl::PointXYZ >::Ptr nan_cloud)
void drawLines (const cv::Mat &nan_image, cv::Mat &dst, const vector< Vec4i > &lines, int max_line_length)
void drawNANs (cv::Mat &nan_image, const Rect roi, double padding=0.0)
void drawProjectedPoints (std::vector< cv::Point2d > &projected_points, cv::Mat &nan_image, cv::Mat &dst)
void drawROI (cv::Mat &nan_image, pcl::PointIndices &roi_indices)
void erodeDilate (cv::Mat &nan_image)
int findBiggestPlane (pcl::PointCloud< pcl::PointXYZRGB >::Ptr pcl_cloud, Rect &roi, pcl::PointIndices &indices_biggest_plane)
void findHandlesInNanPointCloud (pcl::PointCloud< pcl::PointXYZ >::Ptr nan_cloud, std::vector< pcl::PointIndices > &handle_clusters)
void findLines (cv::Mat &nan_image, vector< Vec4i > &lines)
void getHandleImageLength (std::vector< geometry_msgs::PointStamped > &vector_point_avg, std::vector< double > &expected_handle_image_length)
std::string getName () const
 Get a string representation of the name of this class.
 HandleDetectorNANNode (ros::NodeHandle &n)
double lineLength2D (int x1, int y1, int x2, int y2)
double lineLength2D (double x1, double y1, double x2, double y2)
void project3DPointsToPixels (std::vector< cv::Point2d > &projected_points)
void publishMarker (std::vector< geometry_msgs::PointStamped > &vector_point_avg)
void recoverCentroidPose (std::vector< pcl::PointIndices > &handle_clusters, pcl::PointCloud< pcl::PointXYZ >::Ptr nan_cloud, std::vector< geometry_msgs::PointStamped > &vector_point_avg)
void rejectFalsePositives (std::vector< geometry_msgs::PointStamped > &vector_point_avg)
void saveHandleClusters (std::vector< pcl::PointIndices > &handle_clusters, pcl::PointCloud< pcl::PointXYZ >::Ptr nan_cloud)
void transformPoints (std::vector< geometry_msgs::PointStamped > &vector_point_avg, std::string frame="base_link")

Public Attributes

double base_link_kinect_head_rgb_optical_frame_
pcl::PointCloud
< pcl::PointXYZRGB >::Ptr 
biggest_plane_cloud_
sensor_msgs::CameraInfoConstPtr cam_info
image_geometry::PinholeCameraModel cam_model_
Mat canny_img
pcl::ConvexHull< pcl::PointXYZ > chull_
pcl::EuclideanClusterExtraction
< PointT
cluster_
KdTreePtr clusters_tree_
Mat dst
double eps_angle_
pcl::EuclideanClusterExtraction
< pcl::PointXYZ > 
h_cluster_
double handle_length_
pcl::KdTree< pcl::PointXYZ >::Ptr handles_tree_
sensor_msgs::ImageConstPtr image_ptr
string input_cloud_topic_
int k_
std::string kinect_rgb_optical_frame_
ros::Publisher marker_pub_
int max_iter_
int min_table_inliers_
pcl::NormalEstimation
< pcl::PointXYZRGB,
pcl::Normal > 
n3d_
Mat nan_image
double normal_distance_weight_
KdTreePtr normals_tree_
int nr_cluster_
sensor_msgs::PointCloud2 output_cloud_
string output_cloud_topic_
string output_marker_topic_
pcl::PCDWriter pcd_writer_
pcl::PointCloud
< pcl::PointXYZRGB >::Ptr 
pcl_cloud_
int plane_cluster_max_size_
int plane_cluster_min_size_
double plane_cluster_tolerance_
pcl_ros::Publisher< PointTpub_
Mat roi_image
double sac_distance_
bool save_cloud_
bool save_image_
pcl::SACSegmentationFromNormals
< PointT, pcl::Normal > 
seg_
double seg_prob_
ros::ServiceServer service_
ros::Subscriber sub_
tf::TransformListener tf_listener_
double x_handle_position_offset_
double z_handle_position_

Protected Attributes

ros::NodeHandle nh_

Detailed Description

Definition at line 93 of file handle_detector_nan.cpp.


Constructor & Destructor Documentation

Definition at line 130 of file handle_detector_nan.cpp.


Member Function Documentation

Definition at line 712 of file handle_detector_nan.cpp.

void HandleDetectorNANNode::createNaNPointCloud ( cv::Mat &  nan_image,
pcl::PointCloud< pcl::PointXYZ >::Ptr  nan_cloud 
) [inline]

Definition at line 503 of file handle_detector_nan.cpp.

void HandleDetectorNANNode::drawLines ( const cv::Mat &  nan_image,
cv::Mat &  dst,
const vector< Vec4i > &  lines,
int  max_line_length 
) [inline]

Definition at line 470 of file handle_detector_nan.cpp.

void HandleDetectorNANNode::drawNANs ( cv::Mat &  nan_image,
const Rect  roi,
double  padding = 0.0 
) [inline]

Definition at line 403 of file handle_detector_nan.cpp.

void HandleDetectorNANNode::drawProjectedPoints ( std::vector< cv::Point2d > &  projected_points,
cv::Mat &  nan_image,
cv::Mat &  dst 
) [inline]

Definition at line 494 of file handle_detector_nan.cpp.

void HandleDetectorNANNode::drawROI ( cv::Mat &  nan_image,
pcl::PointIndices roi_indices 
) [inline]

Definition at line 423 of file handle_detector_nan.cpp.

void HandleDetectorNANNode::erodeDilate ( cv::Mat &  nan_image) [inline]

Definition at line 460 of file handle_detector_nan.cpp.

int HandleDetectorNANNode::findBiggestPlane ( pcl::PointCloud< pcl::PointXYZRGB >::Ptr  pcl_cloud,
Rect roi,
pcl::PointIndices indices_biggest_plane 
) [inline]

Definition at line 218 of file handle_detector_nan.cpp.

void HandleDetectorNANNode::findHandlesInNanPointCloud ( pcl::PointCloud< pcl::PointXYZ >::Ptr  nan_cloud,
std::vector< pcl::PointIndices > &  handle_clusters 
) [inline]

Definition at line 521 of file handle_detector_nan.cpp.

void HandleDetectorNANNode::findLines ( cv::Mat &  nan_image,
vector< Vec4i > &  lines 
) [inline]

Definition at line 453 of file handle_detector_nan.cpp.

void HandleDetectorNANNode::getHandleImageLength ( std::vector< geometry_msgs::PointStamped > &  vector_point_avg,
std::vector< double > &  expected_handle_image_length 
) [inline]

Definition at line 637 of file handle_detector_nan.cpp.

Get a string representation of the name of this class.

Definition at line 216 of file handle_detector_nan.cpp.

double HandleDetectorNANNode::lineLength2D ( int  x1,
int  y1,
int  x2,
int  y2 
) [inline]

Definition at line 203 of file handle_detector_nan.cpp.

double HandleDetectorNANNode::lineLength2D ( double  x1,
double  y1,
double  x2,
double  y2 
) [inline]

Definition at line 208 of file handle_detector_nan.cpp.

void HandleDetectorNANNode::project3DPointsToPixels ( std::vector< cv::Point2d > &  projected_points) [inline]

Definition at line 384 of file handle_detector_nan.cpp.

void HandleDetectorNANNode::publishMarker ( std::vector< geometry_msgs::PointStamped > &  vector_point_avg) [inline]

Definition at line 603 of file handle_detector_nan.cpp.

void HandleDetectorNANNode::recoverCentroidPose ( std::vector< pcl::PointIndices > &  handle_clusters,
pcl::PointCloud< pcl::PointXYZ >::Ptr  nan_cloud,
std::vector< geometry_msgs::PointStamped > &  vector_point_avg 
) [inline]

Definition at line 548 of file handle_detector_nan.cpp.

void HandleDetectorNANNode::rejectFalsePositives ( std::vector< geometry_msgs::PointStamped > &  vector_point_avg) [inline]

Definition at line 657 of file handle_detector_nan.cpp.

void HandleDetectorNANNode::saveHandleClusters ( std::vector< pcl::PointIndices > &  handle_clusters,
pcl::PointCloud< pcl::PointXYZ >::Ptr  nan_cloud 
) [inline]

Definition at line 531 of file handle_detector_nan.cpp.

void HandleDetectorNANNode::transformPoints ( std::vector< geometry_msgs::PointStamped > &  vector_point_avg,
std::string  frame = "base_link" 
) [inline]

Definition at line 691 of file handle_detector_nan.cpp.


Member Data Documentation

Definition at line 116 of file handle_detector_nan.cpp.

Definition at line 109 of file handle_detector_nan.cpp.

sensor_msgs::CameraInfoConstPtr HandleDetectorNANNode::cam_info

Definition at line 123 of file handle_detector_nan.cpp.

Definition at line 125 of file handle_detector_nan.cpp.

Definition at line 107 of file handle_detector_nan.cpp.

pcl::ConvexHull<pcl::PointXYZ> HandleDetectorNANNode::chull_

Definition at line 127 of file handle_detector_nan.cpp.

Definition at line 114 of file handle_detector_nan.cpp.

Definition at line 111 of file handle_detector_nan.cpp.

Definition at line 107 of file handle_detector_nan.cpp.

Definition at line 116 of file handle_detector_nan.cpp.

Definition at line 115 of file handle_detector_nan.cpp.

Definition at line 117 of file handle_detector_nan.cpp.

pcl::KdTree<pcl::PointXYZ>::Ptr HandleDetectorNANNode::handles_tree_

Definition at line 112 of file handle_detector_nan.cpp.

sensor_msgs::ImageConstPtr HandleDetectorNANNode::image_ptr

Definition at line 124 of file handle_detector_nan.cpp.

Definition at line 99 of file handle_detector_nan.cpp.

Definition at line 118 of file handle_detector_nan.cpp.

Definition at line 128 of file handle_detector_nan.cpp.

Definition at line 103 of file handle_detector_nan.cpp.

Definition at line 118 of file handle_detector_nan.cpp.

Definition at line 118 of file handle_detector_nan.cpp.

pcl::NormalEstimation<pcl::PointXYZRGB, pcl::Normal> HandleDetectorNANNode::n3d_

Definition at line 110 of file handle_detector_nan.cpp.

Definition at line 107 of file handle_detector_nan.cpp.

Definition at line 96 of file handle_detector_nan.cpp.

Definition at line 116 of file handle_detector_nan.cpp.

Definition at line 111 of file handle_detector_nan.cpp.

Definition at line 118 of file handle_detector_nan.cpp.

sensor_msgs::PointCloud2 HandleDetectorNANNode::output_cloud_

Definition at line 105 of file handle_detector_nan.cpp.

Definition at line 99 of file handle_detector_nan.cpp.

Definition at line 99 of file handle_detector_nan.cpp.

Definition at line 126 of file handle_detector_nan.cpp.

Definition at line 108 of file handle_detector_nan.cpp.

Definition at line 120 of file handle_detector_nan.cpp.

Definition at line 120 of file handle_detector_nan.cpp.

Definition at line 119 of file handle_detector_nan.cpp.

Definition at line 104 of file handle_detector_nan.cpp.

Definition at line 107 of file handle_detector_nan.cpp.

Definition at line 116 of file handle_detector_nan.cpp.

Definition at line 122 of file handle_detector_nan.cpp.

Definition at line 122 of file handle_detector_nan.cpp.

Definition at line 113 of file handle_detector_nan.cpp.

Definition at line 116 of file handle_detector_nan.cpp.

Definition at line 102 of file handle_detector_nan.cpp.

Definition at line 101 of file handle_detector_nan.cpp.

Definition at line 121 of file handle_detector_nan.cpp.

Definition at line 117 of file handle_detector_nan.cpp.

Definition at line 117 of file handle_detector_nan.cpp.


The documentation for this class was generated from the following file:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Properties Friends


handle_detection2D
Author(s): Dejan Pangercic
autogenerated on Thu May 23 2013 16:38:45