Adapted version of pcl::RangeImagePlanar. More...
#include <RangeImagePlanar.h>
Public Types | |
typedef boost::shared_ptr < const shape_reconstruction::RangeImagePlanar > | ConstPtr |
typedef boost::shared_ptr < shape_reconstruction::RangeImagePlanar > | Ptr |
Public Member Functions | |
template<typename PointCloudType > | |
void | computeZandMatchingPoints (const PointCloudType &point_cloud, float min_range, const cv::Mat &matching_im, const float matching_im_min_range, pcl::PointIndicesPtr &matching_indices, pcl::PointIndicesPtr &matching_indices_in_matching_im, pcl::PointIndicesPtr &indices_to_remove, int height, int width) |
template<typename PointCloudType > | |
void | createFromPointCloudWithFixedSizeAndStorePoints (const PointCloudType &point_cloud, int di_width, int di_height, float di_center_x, float di_center_y, float di_focal_length_x, float di_focal_length_y, const Eigen::Affine3f &sensor_pose, CoordinateFrame coordinate_frame=CAMERA_FRAME, float noise_level=0.0f, float min_range=0.0f) |
template<typename PointCloudType > | |
void | doZBufferAndStorePoints (const PointCloudType &point_cloud, float noise_level, float min_range, int &top, int &right, int &bottom, int &left) |
bool | getPointIndex (const int &x, const int &y, int &idx) const |
template<typename PointCloudType > | |
void | matchPointCloudAndImage (const PointCloudType &point_cloud, int di_width, int di_height, float di_center_x, float di_center_y, float di_focal_length_x, float di_focal_length_y, const Eigen::Affine3f &sensor_pose, CoordinateFrame coordinate_frame, const cv::Mat &matching_im, const float matching_im_min_range, pcl::PointIndicesPtr &matching_indices, pcl::PointIndicesPtr &matching_indices_in_matching_im, pcl::PointIndicesPtr &indices_to_remove, float min_range=0.0f) |
RangeImagePlanar () | |
void | resetPointIndex (const int &width, const int &height) |
void | setPointIndex (const int &x, const int &y, const int &idx) |
virtual | ~RangeImagePlanar () |
Public Attributes | |
int * | img_coord_to_point_idx |
Adapted version of pcl::RangeImagePlanar.
When creating the RangeImage we additionally track changes to the z-buffer to know which point is projected on which pixel in the range image
Definition at line 66 of file RangeImagePlanar.h.
typedef boost::shared_ptr<const shape_reconstruction::RangeImagePlanar> shape_reconstruction::RangeImagePlanar::ConstPtr |
Definition at line 69 of file RangeImagePlanar.h.
typedef boost::shared_ptr<shape_reconstruction::RangeImagePlanar> shape_reconstruction::RangeImagePlanar::Ptr |
Definition at line 68 of file RangeImagePlanar.h.
Definition at line 71 of file RangeImagePlanar.h.
virtual shape_reconstruction::RangeImagePlanar::~RangeImagePlanar | ( | ) | [inline, virtual] |
Destructor
Definition at line 76 of file RangeImagePlanar.h.
void shape_reconstruction::RangeImagePlanar::computeZandMatchingPoints | ( | const PointCloudType & | point_cloud, |
float | min_range, | ||
const cv::Mat & | matching_im, | ||
const float | matching_im_min_range, | ||
pcl::PointIndicesPtr & | matching_indices, | ||
pcl::PointIndicesPtr & | matching_indices_in_matching_im, | ||
pcl::PointIndicesPtr & | indices_to_remove, | ||
int | height, | ||
int | width | ||
) |
Definition at line 221 of file RangeImagePlanar.hpp.
void shape_reconstruction::RangeImagePlanar::createFromPointCloudWithFixedSizeAndStorePoints | ( | const PointCloudType & | point_cloud, |
int | di_width, | ||
int | di_height, | ||
float | di_center_x, | ||
float | di_center_y, | ||
float | di_focal_length_x, | ||
float | di_focal_length_y, | ||
const Eigen::Affine3f & | sensor_pose, | ||
CoordinateFrame | coordinate_frame = CAMERA_FRAME , |
||
float | noise_level = 0.0f , |
||
float | min_range = 0.0f |
||
) |
Definition at line 179 of file RangeImagePlanar.hpp.
void shape_reconstruction::RangeImagePlanar::doZBufferAndStorePoints | ( | const PointCloudType & | point_cloud, |
float | noise_level, | ||
float | min_range, | ||
int & | top, | ||
int & | right, | ||
int & | bottom, | ||
int & | left | ||
) |
Definition at line 58 of file RangeImagePlanar.hpp.
bool shape_reconstruction::RangeImagePlanar::getPointIndex | ( | const int & | x, |
const int & | y, | ||
int & | idx | ||
) | const [inline] |
Definition at line 121 of file RangeImagePlanar.h.
void shape_reconstruction::RangeImagePlanar::matchPointCloudAndImage | ( | const PointCloudType & | point_cloud, |
int | di_width, | ||
int | di_height, | ||
float | di_center_x, | ||
float | di_center_y, | ||
float | di_focal_length_x, | ||
float | di_focal_length_y, | ||
const Eigen::Affine3f & | sensor_pose, | ||
CoordinateFrame | coordinate_frame, | ||
const cv::Mat & | matching_im, | ||
const float | matching_im_min_range, | ||
pcl::PointIndicesPtr & | matching_indices, | ||
pcl::PointIndicesPtr & | matching_indices_in_matching_im, | ||
pcl::PointIndicesPtr & | indices_to_remove, | ||
float | min_range = 0.0f |
||
) |
Definition at line 451 of file RangeImagePlanar.hpp.
void shape_reconstruction::RangeImagePlanar::resetPointIndex | ( | const int & | width, |
const int & | height | ||
) | [inline] |
Definition at line 141 of file RangeImagePlanar.h.
void shape_reconstruction::RangeImagePlanar::setPointIndex | ( | const int & | x, |
const int & | y, | ||
const int & | idx | ||
) | [inline] |
Definition at line 132 of file RangeImagePlanar.h.
Definition at line 152 of file RangeImagePlanar.h.