#include <edge_estimation_2d.h>
Public Types | |
typedef pcl::PointCloud< PointInT > | PointCloudIn |
typedef boost::shared_ptr < const PointCloudIn > | PointCloudInConstPtr |
typedef boost::shared_ptr < PointCloudIn > | PointCloudInPtr |
typedef pcl::PointCloud < PointOutT > | PointCloudOut |
Public Member Functions | |
void | computeEdges (PointCloudOut &output) |
Computes 2D edges from a color image. | |
void | computeEdges (cv::Mat &sobel_out, cv::Mat &laplace_out, cv::Mat &combined_out) |
Computes 2D edges from a color image. | |
void | computeEdgesFromRange (PointCloudOut &output) |
Computes 2D edges from a range image. | |
void | computeEdgesFromRange (cv::Mat &sobel_out, cv::Mat &laplace_out, cv::Mat &combined_out) |
Computes 2D edges from a range image. | |
EdgeEstimation2D () | |
void | extractEdgesLaPlace (cv::Mat &input_image, cv::Mat &laplace_image) |
Extracts La Place edges from grey image. | |
void | extractEdgesSobel (cv::Mat &input_image, cv::Mat &sobel_image) |
Extracts Sobel edges channel-wise. | |
void | getColorImage (cv::Mat &color_image) |
Creates color image from RGB channel of input_. | |
void | getRangeImage (cv::Mat &range_image, const float &th_min, const float &th_max) |
Creates range image from XYZ channels of input_. | |
void | setInputCloud (const PointCloudInConstPtr &cloud) |
Sets the input cloud. | |
~EdgeEstimation2D () | |
Protected Attributes | |
PointCloudInConstPtr | input_ |
Definition at line 73 of file edge_estimation_2d.h.
typedef pcl::PointCloud<PointInT> cob_3d_features::EdgeEstimation2D< PointInT, PointOutT >::PointCloudIn |
Definition at line 77 of file edge_estimation_2d.h.
typedef boost::shared_ptr<const PointCloudIn> cob_3d_features::EdgeEstimation2D< PointInT, PointOutT >::PointCloudInConstPtr |
Definition at line 81 of file edge_estimation_2d.h.
typedef boost::shared_ptr<PointCloudIn> cob_3d_features::EdgeEstimation2D< PointInT, PointOutT >::PointCloudInPtr |
Definition at line 80 of file edge_estimation_2d.h.
typedef pcl::PointCloud<PointOutT> cob_3d_features::EdgeEstimation2D< PointInT, PointOutT >::PointCloudOut |
Definition at line 82 of file edge_estimation_2d.h.
cob_3d_features::EdgeEstimation2D< PointInT, PointOutT >::EdgeEstimation2D | ( | ) | [inline] |
Definition at line 76 of file edge_estimation_2d.h.
cob_3d_features::EdgeEstimation2D< PointInT, PointOutT >::~EdgeEstimation2D | ( | ) | [inline] |
Definition at line 77 of file edge_estimation_2d.h.
void cob_3d_features::EdgeEstimation2D< PointInT, PointOutT >::computeEdges | ( | PointCloudOut & | output | ) |
Computes 2D edges from a color image.
output | Edge point cloud. |
Definition at line 181 of file edge_estimation_2d.hpp.
void cob_3d_features::EdgeEstimation2D< PointInT, PointOutT >::computeEdges | ( | cv::Mat & | sobel_out, |
cv::Mat & | laplace_out, | ||
cv::Mat & | combined_out | ||
) |
Computes 2D edges from a color image.
sobel_out | Sobel output image (CV_32FC1). |
laplace_out | La Place output image (CV_32FC1). |
combined_out | Combined Sobel and La Place output image (CV_32FC1). |
Definition at line 212 of file edge_estimation_2d.hpp.
void cob_3d_features::EdgeEstimation2D< PointInT, PointOutT >::computeEdgesFromRange | ( | PointCloudOut & | output | ) |
Computes 2D edges from a range image.
output | Edge point cloud. |
Definition at line 233 of file edge_estimation_2d.hpp.
void cob_3d_features::EdgeEstimation2D< PointInT, PointOutT >::computeEdgesFromRange | ( | cv::Mat & | sobel_out, |
cv::Mat & | laplace_out, | ||
cv::Mat & | combined_out | ||
) |
Computes 2D edges from a range image.
sobel_out | Sobel output image (CV_32FC1). |
laplace_out | La Place output image (CV_32FC1). |
combined_out | Combined Sobel and La Place output image (CV_32FC1). |
Definition at line 258 of file edge_estimation_2d.hpp.
void cob_3d_features::EdgeEstimation2D< PointInT, PointOutT >::extractEdgesLaPlace | ( | cv::Mat & | input_image, |
cv::Mat & | laplace_image | ||
) |
Extracts La Place edges from grey image.
image | The input color or grey image (CV_8UC3 or CV_8UC1). |
laplace_image | La Place output image (CV_32FC1). |
Definition at line 151 of file edge_estimation_2d.hpp.
void cob_3d_features::EdgeEstimation2D< PointInT, PointOutT >::extractEdgesSobel | ( | cv::Mat & | input_image, |
cv::Mat & | sobel_image | ||
) |
Extracts Sobel edges channel-wise.
input_image | The input color or grey image (CV_8UC3 or CV_8UC1). |
sobel_image | Sobel output image (CV_32FC1). |
Definition at line 112 of file edge_estimation_2d.hpp.
void cob_3d_features::EdgeEstimation2D< PointInT, PointOutT >::getColorImage | ( | cv::Mat & | color_image | ) |
Creates color image from RGB channel of input_.
color_image | The color image returned. |
Definition at line 70 of file edge_estimation_2d.hpp.
void cob_3d_features::EdgeEstimation2D< PointInT, PointOutT >::getRangeImage | ( | cv::Mat & | range_image, |
const float & | th_min = 0.0f , |
||
const float & | th_max = 0.0f |
||
) |
Creates range image from XYZ channels of input_.
range_image | The range image returned. |
th_min | Minimum range threshold (default 0.0). |
th_max | Maximum range threshold (default 0.0). |
Definition at line 87 of file edge_estimation_2d.hpp.
void cob_3d_features::EdgeEstimation2D< PointInT, PointOutT >::setInputCloud | ( | const PointCloudInConstPtr & | cloud | ) | [inline] |
Sets the input cloud.
cloud | The cloud to set as input_. |
Definition at line 90 of file edge_estimation_2d.h.
PointCloudInConstPtr cob_3d_features::EdgeEstimation2D< PointInT, PointOutT >::input_ [protected] |
Definition at line 162 of file edge_estimation_2d.h.