Public Types | Public Member Functions | Protected Attributes
pcl::RangeImagePlanar Class Reference

RangeImagePlanar is derived from the original range image and differs from it because it's not a spherical projection, but using a projection plane (as normal cameras do), therefore being better applicable for range sensors that already provide a range image by themselves (stereo cameras, ToF-cameras), so that a conversion to point cloud and then to a spherical range image becomes unnecessary. More...

#include <range_image_planar.h>

Inheritance diagram for pcl::RangeImagePlanar:
Inheritance graph
[legend]

List of all members.

Public Types

typedef RangeImage BaseClass
typedef boost::shared_ptr
< const RangeImagePlanar
ConstPtr
typedef boost::shared_ptr
< RangeImagePlanar
Ptr

Public Member Functions

virtual void calculate3DPoint (float image_x, float image_y, float range, Eigen::Vector3f &point) const
 Calculate the 3D point according to the given image point and range.
template<typename PointCloudType >
void createFromPointCloudWithFixedSize (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)
virtual PCL_EXPORTS void getHalfImage (RangeImage &half_image) const
 Get a range image with half the resolution.
virtual void getImagePoint (const Eigen::Vector3f &point, float &image_x, float &image_y, float &range) const
 Calculate the image point and range from the given 3D point.
virtual RangeImagegetNew () const
virtual PCL_EXPORTS void getSubImage (int sub_image_image_offset_x, int sub_image_image_offset_y, int sub_image_width, int sub_image_height, int combine_pixels, RangeImage &sub_image) const
Ptr makeShared ()
 Get a boost shared pointer of a copy of this.
PCL_EXPORTS RangeImagePlanar ()
PCL_EXPORTS void setDepthImage (const float *depth_image, int di_width, int di_height, float di_center_x, float di_center_y, float di_focal_length_x, float di_focal_length_y, float desired_angular_resolution=-1)
PCL_EXPORTS void setDepthImage (const unsigned short *depth_image, int di_width, int di_height, float di_center_x, float di_center_y, float di_focal_length_x, float di_focal_length_y, float desired_angular_resolution=-1)
PCL_EXPORTS void setDisparityImage (const float *disparity_image, int di_width, int di_height, float focal_length, float base_line, float desired_angular_resolution=-1)
 Create the image from an existing disparity image.
PCL_EXPORTS ~RangeImagePlanar ()

Protected Attributes

float center_x_
float center_y_
 The principle point of the image.
float focal_length_x_
float focal_length_x_reciprocal_
float focal_length_y_
 The focal length of the image in pixels.
float focal_length_y_reciprocal_
 1/focal_length -> for internal use

Detailed Description

RangeImagePlanar is derived from the original range image and differs from it because it's not a spherical projection, but using a projection plane (as normal cameras do), therefore being better applicable for range sensors that already provide a range image by themselves (stereo cameras, ToF-cameras), so that a conversion to point cloud and then to a spherical range image becomes unnecessary.

Author:
Bastian Steder

Definition at line 49 of file range_image_planar.h.


Member Typedef Documentation

Reimplemented from pcl::RangeImage.

Definition at line 53 of file range_image_planar.h.

typedef boost::shared_ptr<const RangeImagePlanar> pcl::RangeImagePlanar::ConstPtr

Reimplemented from pcl::RangeImage.

Definition at line 55 of file range_image_planar.h.

typedef boost::shared_ptr<RangeImagePlanar> pcl::RangeImagePlanar::Ptr

Reimplemented from pcl::RangeImage.

Definition at line 54 of file range_image_planar.h.


Constructor & Destructor Documentation

Constructor

Definition at line 46 of file range_image_planar.cpp.

Destructor

Definition at line 53 of file range_image_planar.cpp.


Member Function Documentation

void pcl::RangeImagePlanar::calculate3DPoint ( float  image_x,
float  image_y,
float  range,
Eigen::Vector3f &  point 
) const [inline, virtual]

Calculate the 3D point according to the given image point and range.

Parameters:
image_xthe x image position
image_ythe y image position
rangethe range
pointthe resulting 3D point
Note:
Implementation according to planar range images (compared to spherical as in the original)

Reimplemented from pcl::RangeImage.

Definition at line 86 of file range_image_planar.hpp.

template<typename PointCloudType >
void pcl::RangeImagePlanar::createFromPointCloudWithFixedSize ( 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 
)

Create the image from an existing point cloud.

Parameters:
point_cloudthe source point cloud
di_widththe disparity image width
di_heightthe disparity image height
di_center_xthe x-coordinate of the camera's center of projection
di_center_ythe y-coordinate of the camera's center of projection
di_focal_length_xthe camera's focal length in the horizontal direction
di_focal_length_ythe camera's focal length in the vertical direction
sensor_posethe pose of the virtual depth camera
coordinate_framethe used coordinate frame of the point cloud
noise_levelwhat is the typical noise of the sensor - is used for averaging in the z-buffer
min_rangeminimum range to consifder points

Definition at line 44 of file range_image_planar.hpp.

void pcl::RangeImagePlanar::getHalfImage ( RangeImage half_image) const [virtual]

Get a range image with half the resolution.

Reimplemented from pcl::RangeImage.

Definition at line 207 of file range_image_planar.cpp.

void pcl::RangeImagePlanar::getImagePoint ( const Eigen::Vector3f &  point,
float &  image_x,
float &  image_y,
float &  range 
) const [inline, virtual]

Calculate the image point and range from the given 3D point.

Parameters:
pointthe resulting 3D point
image_xthe resulting x image position
image_ythe resulting y image position
rangethe resulting range
Note:
Implementation according to planar range images (compared to spherical as in the original)

Reimplemented from pcl::RangeImage.

Definition at line 99 of file range_image_planar.hpp.

virtual RangeImage* pcl::RangeImagePlanar::getNew ( ) const [inline, virtual]

Return a newly created RangeImagePlanar. Reimplmentation to return an image of the same type.

Reimplemented from pcl::RangeImage.

Definition at line 66 of file range_image_planar.h.

void pcl::RangeImagePlanar::getSubImage ( int  sub_image_image_offset_x,
int  sub_image_image_offset_y,
int  sub_image_width,
int  sub_image_height,
int  combine_pixels,
RangeImage sub_image 
) const [virtual]

Get a sub part of the complete image as a new range image.

Parameters:
sub_image_image_offset_x- The x coordinate of the top left pixel of the sub image. This is always according to absolute 0,0 meaning -180°,-90° and it is already in the system of the new image, so the actual pixel used in the original image is combine_pixels* (image_offset_x-image_offset_x_)
sub_image_image_offset_y- Same as image_offset_x for the y coordinate
sub_image_width- width of the new image
sub_image_height- height of the new image
combine_pixels- shrinking factor, meaning the new angular resolution is combine_pixels times the old one
sub_image- the output image

Reimplemented from pcl::RangeImage.

Definition at line 228 of file range_image_planar.cpp.

Get a boost shared pointer of a copy of this.

Reimplemented from pcl::RangeImage.

Definition at line 71 of file range_image_planar.h.

void pcl::RangeImagePlanar::setDepthImage ( const float *  depth_image,
int  di_width,
int  di_height,
float  di_center_x,
float  di_center_y,
float  di_focal_length_x,
float  di_focal_length_y,
float  desired_angular_resolution = -1 
)

Create the image from an existing depth image.

Parameters:
depth_imagethe input depth image data as float values
di_widththe disparity image width
di_heightthe disparity image height
di_center_xthe x-coordinate of the camera's center of projection
di_center_ythe y-coordinate of the camera's center of projection
di_focal_length_xthe camera's focal length in the horizontal direction
di_focal_length_ythe camera's focal length in the vertical direction
desired_angular_resolutionIf this is set, the system will skip as many pixels as necessary to get as close to this angular resolution as possible while not going over this value (the density will not be lower than this value). The value is in radians per pixel.

Definition at line 116 of file range_image_planar.cpp.

void pcl::RangeImagePlanar::setDepthImage ( const unsigned short *  depth_image,
int  di_width,
int  di_height,
float  di_center_x,
float  di_center_y,
float  di_focal_length_x,
float  di_focal_length_y,
float  desired_angular_resolution = -1 
)

Create the image from an existing depth image.

Parameters:
depth_imagethe input disparity image data as short values describing millimeters
di_widththe disparity image width
di_heightthe disparity image height
di_center_xthe x-coordinate of the camera's center of projection
di_center_ythe y-coordinate of the camera's center of projection
di_focal_length_xthe camera's focal length in the horizontal direction
di_focal_length_ythe camera's focal length in the vertical direction
desired_angular_resolutionIf this is set, the system will skip as many pixels as necessary to get as close to this angular resolution as possible while not going over this value (the density will not be lower than this value). The value is in radians per pixel.

Definition at line 162 of file range_image_planar.cpp.

void pcl::RangeImagePlanar::setDisparityImage ( const float *  disparity_image,
int  di_width,
int  di_height,
float  focal_length,
float  base_line,
float  desired_angular_resolution = -1 
)

Create the image from an existing disparity image.

Parameters:
disparity_imagethe input disparity image data
di_widththe disparity image width
di_heightthe disparity image height
focal_lengththe focal length of the primary camera that generated the disparity image
base_linethe baseline of the stereo pair that generated the disparity image
desired_angular_resolutionIf this is set, the system will skip as many pixels as necessary to get as close to this angular resolution as possible while not going over this value (the density will not be lower than this value). The value is in radians per pixel.

Definition at line 59 of file range_image_planar.cpp.


Member Data Documentation

Definition at line 188 of file range_image_planar.h.

The principle point of the image.

Definition at line 188 of file range_image_planar.h.

Definition at line 186 of file range_image_planar.h.

Definition at line 187 of file range_image_planar.h.

The focal length of the image in pixels.

Definition at line 186 of file range_image_planar.h.

1/focal_length -> for internal use

Definition at line 187 of file range_image_planar.h.


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


pcl
Author(s): Open Perception
autogenerated on Mon Oct 6 2014 03:19:58