Definition at line 93 of file handle_detector_nan.cpp.
HandleDetectorNANNode::HandleDetectorNANNode | ( | ros::NodeHandle & | n | ) | [inline] |
Definition at line 130 of file handle_detector_nan.cpp.
bool HandleDetectorNANNode::cloud_cb | ( | handle_detection2D::getHandlesNAN::Request & | req, |
handle_detection2D::getHandlesNAN::Response & | res | ||
) | [inline] |
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.
std::string HandleDetectorNANNode::getName | ( | ) | const [inline] |
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.
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.
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.
Definition at line 110 of file handle_detector_nan.cpp.
Definition at line 107 of file handle_detector_nan.cpp.
ros::NodeHandle HandleDetectorNANNode::nh_ [protected] |
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.